diff --git a/mavlink_lib.py b/mavlink_lib.py
index 56abc47a09dfffe4f17baeccf72961f5046e7c88..5bb020fdb93f9a950d3202d79eabdb3d21aa9273 100644
--- a/mavlink_lib.py
+++ b/mavlink_lib.py
@@ -1,20 +1,22 @@
-'''
+"""
 MAVLink protocol implementation (auto-generated by mavgen.py)
 
-Generated from: lyra.xml
+Generated from: ('lyra.xml',)
 
 Note: this file has been auto-generated. DO NOT EDIT
-'''
-from __future__ import print_function
-from builtins import range
-from builtins import object
-import struct, array, time, json, os, sys, platform
-
-from pymavlink.generator.mavcrc import x25crc
+"""
 import hashlib
-
-WIRE_PROTOCOL_VERSION = '1.0'
-DIALECT = 'mavlink_lib'
+import json
+import logging
+import os
+import struct
+import sys
+import time
+from builtins import object, range
+from typing import Any, Callable, Dict, Iterable, List, Mapping, Optional, Sequence, Tuple, Type, Union, cast
+
+WIRE_PROTOCOL_VERSION = "1.0"
+DIALECT = "mavlink_lib"
 
 PROTOCOL_MARKER_V1 = 0xFE
 PROTOCOL_MARKER_V2 = 0xFD
@@ -25,67 +27,54 @@ MAVLINK_SIGNATURE_BLOCK_LEN = 13
 
 MAVLINK_IFLAG_SIGNED = 0x01
 
-native_supported = platform.system() != 'Windows' # Not yet supported on other dialects
-native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants
-native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared
+if sys.version_info[0] == 2:
+    logging.basicConfig()
 
-if native_supported and float(WIRE_PROTOCOL_VERSION) <= 1:
-    try:
-        import mavnative
-    except ImportError:
-        print('ERROR LOADING MAVNATIVE - falling back to python implementation')
-        native_supported = False
-else:
-    # mavnative isn't supported for MAVLink2 yet
-    native_supported = False
+logger = logging.getLogger(__name__)
 
 # allow MAV_IGNORE_CRC=1 to ignore CRC, allowing some
 # corrupted msgs to be seen
-MAVLINK_IGNORE_CRC = os.environ.get("MAV_IGNORE_CRC",0)
+MAVLINK_IGNORE_CRC = os.environ.get("MAV_IGNORE_CRC", 0)
 
 # some base types from mavlink_types.h
-MAVLINK_TYPE_CHAR     = 0
-MAVLINK_TYPE_UINT8_T  = 1
-MAVLINK_TYPE_INT8_T   = 2
+MAVLINK_TYPE_CHAR = 0
+MAVLINK_TYPE_UINT8_T = 1
+MAVLINK_TYPE_INT8_T = 2
 MAVLINK_TYPE_UINT16_T = 3
-MAVLINK_TYPE_INT16_T  = 4
+MAVLINK_TYPE_INT16_T = 4
 MAVLINK_TYPE_UINT32_T = 5
-MAVLINK_TYPE_INT32_T  = 6
+MAVLINK_TYPE_INT32_T = 6
 MAVLINK_TYPE_UINT64_T = 7
-MAVLINK_TYPE_INT64_T  = 8
-MAVLINK_TYPE_FLOAT    = 9
-MAVLINK_TYPE_DOUBLE   = 10
-
-
-# swiped from DFReader.py
-def to_string(s):
-    '''desperate attempt to convert a string regardless of what garbage we get'''
-    try:
-        return s.decode("utf-8")
-    except Exception as e:
-        pass
-    try:
-        s2 = s.encode('utf-8', 'ignore')
-        x = u"%s" % s2
-        return s2
-    except Exception:
-        pass
-    # so it's a nasty one. Let's grab as many characters as we can
-    r = ''
-    try:
-        for c in s:
-            r2 = r + c
-            r2 = r2.encode('ascii', 'ignore')
-            x = u"%s" % r2
-            r = r2
-    except Exception:
-        pass
-    return r + '_XXX'
+MAVLINK_TYPE_INT64_T = 8
+MAVLINK_TYPE_FLOAT = 9
+MAVLINK_TYPE_DOUBLE = 10
+
+
+class x25crc(object):
+    """CRC-16/MCRF4XX - based on checksum.h from mavlink library"""
+
+    def __init__(self, buf: Optional[Sequence[int]] = None) -> None:
+        self.crc = 0xFFFF
+        if buf is not None:
+            self.accumulate(buf)
+
+    def accumulate(self, buf: Sequence[int]) -> None:
+        """add in some more bytes (it also accepts python2 strings)"""
+        if sys.version_info[0] == 2 and type(buf) is str:
+            buf = bytearray(buf)
+
+        accum = self.crc
+        for b in buf:
+            tmp = b ^ (accum & 0xFF)
+            tmp = (tmp ^ (tmp << 4)) & 0xFF
+            accum = (accum >> 8) ^ (tmp << 8) ^ (tmp << 3) ^ (tmp >> 4)
+        self.crc = accum
 
 
 class MAVLink_header(object):
-    '''MAVLink message header'''
-    def __init__(self, msgId, incompat_flags=0, compat_flags=0, mlen=0, seq=0, srcSystem=0, srcComponent=0):
+    """MAVLink message header"""
+
+    def __init__(self, msgId: int, incompat_flags: int = 0, compat_flags: int = 0, mlen: int = 0, seq: int = 0, srcSystem: int = 0, srcComponent: int = 0) -> None:
         self.mlen = mlen
         self.seq = seq
         self.srcSystem = srcSystem
@@ -94,95 +83,131 @@ class MAVLink_header(object):
         self.incompat_flags = incompat_flags
         self.compat_flags = compat_flags
 
-    def pack(self, force_mavlink1=False):
-        if WIRE_PROTOCOL_VERSION == '2.0' and not force_mavlink1:
-            return struct.pack('<BBBBBBBHB', 254, self.mlen,
-                               self.incompat_flags, self.compat_flags,
-                               self.seq, self.srcSystem, self.srcComponent,
-                               self.msgId&0xFFFF, self.msgId>>16)
-        return struct.pack('<BBBBBB', PROTOCOL_MARKER_V1, self.mlen, self.seq,
-                           self.srcSystem, self.srcComponent, self.msgId)
+    def pack(self, force_mavlink1: bool = False) -> bytes:
+        if float(WIRE_PROTOCOL_VERSION) == 2.0 and not force_mavlink1:
+            return struct.pack(
+                "<BBBBBBBHB",
+                254,
+                self.mlen,
+                self.incompat_flags,
+                self.compat_flags,
+                self.seq,
+                self.srcSystem,
+                self.srcComponent,
+                self.msgId & 0xFFFF,
+                self.msgId >> 16,
+            )
+        return struct.pack(
+            "<BBBBBB",
+            PROTOCOL_MARKER_V1,
+            self.mlen,
+            self.seq,
+            self.srcSystem,
+            self.srcComponent,
+            self.msgId,
+        )
 
-class MAVLink_message(object):
-    '''base MAVLink message class'''
-    def __init__(self, msgId, name):
-        self._header     = MAVLink_header(msgId)
-        self._payload    = None
-        self._msgbuf     = None
-        self._crc        = None
-        self._fieldnames = []
-        self._type       = name
-        self._signed     = False
-        self._link_id    = None
-        self._instances  = None
-        self._instance_field = None
 
-    def format_attr(self, field):
-        '''override field getter'''
-        raw_attr = getattr(self,field)
+class MAVLink_message(object):
+    """base MAVLink message class"""
+
+    id = 0
+    msgname = ""
+    fieldnames: List[str] = []
+    ordered_fieldnames: List[str] = []
+    fieldtypes: List[str] = []
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"")
+    orders: List[int] = []
+    lengths: List[int] = []
+    array_lengths: List[int] = []
+    crc_extra = 0
+    unpacker = struct.Struct("")
+    instance_field: Optional[str] = None
+    instance_offset = -1
+
+    def __init__(self, msgId: int, name: str) -> None:
+        self._header = MAVLink_header(msgId)
+        self._payload: Optional[bytes] = None
+        self._msgbuf = bytearray(b"")
+        self._crc: Optional[int] = None
+        self._fieldnames: List[str] = []
+        self._type = name
+        self._signed = False
+        self._link_id: Optional[int] = None
+        self._instances: Optional[Dict[str, str]] = None
+        self._instance_field: Optional[str] = None
+
+    def format_attr(self, field: str) -> Union[str, float, int]:
+        """override field getter"""
+        raw_attr = cast(Union[bytes, float, int], getattr(self, field))
         if isinstance(raw_attr, bytes):
-            raw_attr = to_string(raw_attr).rstrip("\00")
+            if sys.version_info[0] == 2:
+                return raw_attr.rstrip(b"\x00")
+            return raw_attr.decode(errors="backslashreplace").rstrip("\x00")
         return raw_attr
 
-    def get_msgbuf(self):
-        if isinstance(self._msgbuf, bytearray):
-            return self._msgbuf
-        return bytearray(self._msgbuf)
+    def get_msgbuf(self) -> bytearray:
+        return self._msgbuf
 
-    def get_header(self):
+    def get_header(self) -> MAVLink_header:
         return self._header
 
-    def get_payload(self):
+    def get_payload(self) -> Optional[bytes]:
         return self._payload
 
-    def get_crc(self):
+    def get_crc(self) -> Optional[int]:
         return self._crc
 
-    def get_fieldnames(self):
+    def get_fieldnames(self) -> List[str]:
         return self._fieldnames
 
-    def get_type(self):
+    def get_type(self) -> str:
         return self._type
 
-    def get_msgId(self):
+    def get_msgId(self) -> int:
         return self._header.msgId
 
-    def get_srcSystem(self):
+    def get_srcSystem(self) -> int:
         return self._header.srcSystem
 
-    def get_srcComponent(self):
+    def get_srcComponent(self) -> int:
         return self._header.srcComponent
 
-    def get_seq(self):
+    def get_seq(self) -> int:
         return self._header.seq
 
-    def get_signed(self):
+    def get_signed(self) -> bool:
         return self._signed
 
-    def get_link_id(self):
+    def get_link_id(self) -> Optional[int]:
         return self._link_id
 
-    def __str__(self):
-        ret = '%s {' % self._type
+    def __str__(self) -> str:
+        ret = "%s {" % self._type
         for a in self._fieldnames:
             v = self.format_attr(a)
-            ret += '%s : %s, ' % (a, v)
-        ret = ret[0:-2] + '}'
+            ret += "%s : %s, " % (a, v)
+        ret = ret[0:-2] + "}"
         return ret
 
-    def __ne__(self, other):
+    def __ne__(self, other: object) -> bool:
         return not self.__eq__(other)
 
-    def __eq__(self, other):
+    def __eq__(self, other: object) -> bool:
         if other is None:
             return False
 
+        if not isinstance(other, MAVLink_message):
+            return False
+
         if self.get_type() != other.get_type():
             return False
 
-        # We do not compare CRC because native code doesn't provide it
-        #if self.get_crc() != other.get_crc():
-        #    return False
+        if self.get_crc() != other.get_crc():
+            return False
 
         if self.get_seq() != other.get_seq():
             return False
@@ -199,282 +224,343 @@ class MAVLink_message(object):
 
         return True
 
-    def to_dict(self):
-        d = dict({})
-        d['mavpackettype'] = self._type
+    def to_dict(self) -> Dict[str, Union[str, float, int]]:
+        d: Dict[str, Union[str, float, int]] = {}
+        d["mavpackettype"] = self._type
         for a in self._fieldnames:
-          d[a] = self.format_attr(a)
+            d[a] = self.format_attr(a)
         return d
 
-    def to_json(self):
+    def to_json(self) -> str:
         return json.dumps(self.to_dict())
 
-    def sign_packet(self, mav):
-        h = hashlib.new('sha256')
-        self._msgbuf += struct.pack('<BQ', mav.signing.link_id, mav.signing.timestamp)[:7]
+    def sign_packet(self, mav: "MAVLink") -> None:
+        assert mav.signing.secret_key is not None
+
+        h = hashlib.new("sha256")
+        self._msgbuf += struct.pack("<BQ", mav.signing.link_id, mav.signing.timestamp)[:7]
         h.update(mav.signing.secret_key)
         h.update(self._msgbuf)
         sig = h.digest()[:6]
         self._msgbuf += sig
         mav.signing.timestamp += 1
 
-    def pack(self, mav, crc_extra, payload, force_mavlink1=False):
+    def _pack(self, mav: "MAVLink", crc_extra: int, payload: bytes, force_mavlink1: bool = False) -> bytes:
         plen = len(payload)
-        if WIRE_PROTOCOL_VERSION != '1.0' and not force_mavlink1:
+        if float(WIRE_PROTOCOL_VERSION) == 2.0 and not force_mavlink1:
             # in MAVLink2 we can strip trailing zeros off payloads. This allows for simple
             # variable length arrays and smaller packets
-            nullbyte = chr(0)
-            # in Python2, type("fred') is str but also type("fred")==bytes
-            if str(type(payload)) == "<class 'bytes'>":
+            if sys.version_info[0] == 2:
+                nullbyte = chr(0)
+            else:
                 nullbyte = 0
-            while plen > 1 and payload[plen-1] == nullbyte:
+            while plen > 1 and payload[plen - 1] == nullbyte:
                 plen -= 1
         self._payload = payload[:plen]
         incompat_flags = 0
         if mav.signing.sign_outgoing:
             incompat_flags |= MAVLINK_IFLAG_SIGNED
-        self._header  = MAVLink_header(self._header.msgId,
-                                       incompat_flags=incompat_flags, compat_flags=0,
-                                       mlen=len(self._payload), seq=mav.seq,
-                                       srcSystem=mav.srcSystem, srcComponent=mav.srcComponent)
-        self._msgbuf = self._header.pack(force_mavlink1=force_mavlink1) + self._payload
+        self._header = MAVLink_header(
+            self._header.msgId,
+            incompat_flags=incompat_flags,
+            compat_flags=0,
+            mlen=len(self._payload),
+            seq=mav.seq,
+            srcSystem=mav.srcSystem,
+            srcComponent=mav.srcComponent,
+        )
+        self._msgbuf = bytearray(self._header.pack(force_mavlink1=force_mavlink1))
+        self._msgbuf += self._payload
         crc = x25crc(self._msgbuf[1:])
-        if True: # using CRC extra
-            crc.accumulate_str(struct.pack('B', crc_extra))
+        if True:
+            # we are using CRC extra
+            crc.accumulate(struct.pack("B", crc_extra))
         self._crc = crc.crc
-        self._msgbuf += struct.pack('<H', self._crc)
+        self._msgbuf += struct.pack("<H", self._crc)
         if mav.signing.sign_outgoing and not force_mavlink1:
             self.sign_packet(mav)
-        return self._msgbuf
+        return bytes(self._msgbuf)
 
-    def __getitem__(self, key):
-        '''support indexing, allowing for multi-instance sensors in one message'''
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        raise NotImplementedError("MAVLink_message cannot be serialized directly")
+
+    def __getitem__(self, key: str) -> str:
+        """support indexing, allowing for multi-instance sensors in one message"""
         if self._instances is None:
             raise IndexError()
-        if not key in self._instances:
+        if key not in self._instances:
             raise IndexError()
         return self._instances[key]
 
 
+class mavlink_msg_deprecated_name_property(object):
+    """
+    This handles the class variable name change from name to msgname for
+    subclasses of MAVLink_message during a transition period.
+
+    This is used by setting the class variable to
+    `mavlink_msg_deprecated_name_property()`.
+    """
+
+    def __get__(self, instance: Optional[MAVLink_message], owner: Type[MAVLink_message]) -> str:
+        if instance is not None:
+            logger.error("Using .name on a MAVLink_message is not supported, use .get_type() instead.")
+            raise AttributeError("Class {} has no attribute 'name'".format(owner.__name__))
+        logger.warning(
+            """Using .name on a MAVLink_message class is deprecated, consider using .msgname instead.
+Note that if compatibility with pymavlink 2.4.30 and earlier is desired, use something like this:
+
+msg_name =  msg.msgname if hasattr(msg, "msgname") else msg.name"""
+        )
+        return owner.msgname
+
+
 # enums
 
+
 class EnumEntry(object):
-    def __init__(self, name, description):
+    def __init__(self, name: str, description: str) -> None:
         self.name = name
         self.description = description
-        self.param = {}
+        self.param: Dict[int, str] = {}
+        self.has_location = False
 
-enums = {}
+
+enums: Dict[str, Dict[int, EnumEntry]] = {}
 
 # SysIDs
-enums['SysIDs'] = {}
-MAV_SYSID_MAIN = 1 # 
-enums['SysIDs'][1] = EnumEntry('MAV_SYSID_MAIN', '''''')
-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', '''''')
-SysIDs_ENUM_END = 5 # 
-enums['SysIDs'][5] = EnumEntry('SysIDs_ENUM_END', '''''')
+enums["SysIDs"] = {}
+MAV_SYSID_MAIN = 1
+enums["SysIDs"][1] = EnumEntry("MAV_SYSID_MAIN", """""")
+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", """""")
+SysIDs_ENUM_END = 6
+enums["SysIDs"][6] = EnumEntry("SysIDs_ENUM_END", """""")
 
 # SystemTMList
-enums['SystemTMList'] = {}
-MAV_SYS_ID = 1 # State of init results about system hardware/software components
-enums['SystemTMList'][1] = EnumEntry('MAV_SYS_ID', '''State of init results about system hardware/software components''')
-MAV_PIN_OBS_ID = 2 # Pin observer data
-enums['SystemTMList'][2] = EnumEntry('MAV_PIN_OBS_ID', '''Pin observer data''')
-MAV_LOGGER_ID = 3 # SD Logger stats
-enums['SystemTMList'][3] = EnumEntry('MAV_LOGGER_ID', '''SD Logger stats''')
-MAV_MAVLINK_STATS_ID = 4 # Mavlink driver stats
-enums['SystemTMList'][4] = EnumEntry('MAV_MAVLINK_STATS_ID', '''Mavlink driver stats''')
-MAV_TASK_STATS_ID = 5 # Task scheduler statistics answer: n mavlink messages where n is the
-                        # number of tasks
-enums['SystemTMList'][5] = EnumEntry('MAV_TASK_STATS_ID', '''Task scheduler statistics answer: n mavlink messages where n is the number of tasks''')
-MAV_ADA_ID = 6 # ADA Status
-enums['SystemTMList'][6] = EnumEntry('MAV_ADA_ID', '''ADA Status''')
-MAV_NAS_ID = 7 # NavigationSystem data
-enums['SystemTMList'][7] = EnumEntry('MAV_NAS_ID', '''NavigationSystem data''')
-MAV_MEA_ID = 8 # MEA Status
-enums['SystemTMList'][8] = EnumEntry('MAV_MEA_ID', '''MEA Status''')
-MAV_CAN_STATS_ID = 9 # Canbus stats
-enums['SystemTMList'][9] = EnumEntry('MAV_CAN_STATS_ID', '''Canbus stats''')
-MAV_FLIGHT_ID = 10 # Flight telemetry
-enums['SystemTMList'][10] = EnumEntry('MAV_FLIGHT_ID', '''Flight telemetry''')
-MAV_STATS_ID = 11 # Satistics telemetry
-enums['SystemTMList'][11] = EnumEntry('MAV_STATS_ID', '''Satistics telemetry''')
-MAV_SENSORS_STATE_ID = 12 # Sensors init state telemetry
-enums['SystemTMList'][12] = EnumEntry('MAV_SENSORS_STATE_ID', '''Sensors init state telemetry''')
-MAV_GSE_ID = 13 # Ground Segnement Equipment
-enums['SystemTMList'][13] = EnumEntry('MAV_GSE_ID', '''Ground Segnement Equipment''')
-MAV_MOTOR_ID = 14 # Rocket Motor data
-enums['SystemTMList'][14] = EnumEntry('MAV_MOTOR_ID', '''Rocket Motor data''')
-MAV_REGISTRY_ID = 15 # Command to fetch all registry keys
-enums['SystemTMList'][15] = EnumEntry('MAV_REGISTRY_ID', '''Command to fetch all registry keys''')
-SystemTMList_ENUM_END = 16 # 
-enums['SystemTMList'][16] = EnumEntry('SystemTMList_ENUM_END', '''''')
+enums["SystemTMList"] = {}
+MAV_SYS_ID = 1
+enums["SystemTMList"][1] = EnumEntry("MAV_SYS_ID", """State of init results about system hardware/software components""")
+MAV_PIN_OBS_ID = 2
+enums["SystemTMList"][2] = EnumEntry("MAV_PIN_OBS_ID", """Pin observer data""")
+MAV_LOGGER_ID = 3
+enums["SystemTMList"][3] = EnumEntry("MAV_LOGGER_ID", """SD Logger stats""")
+MAV_MAVLINK_STATS_ID = 4
+enums["SystemTMList"][4] = EnumEntry("MAV_MAVLINK_STATS_ID", """Mavlink driver stats""")
+MAV_TASK_STATS_ID = 5
+enums["SystemTMList"][5] = EnumEntry("MAV_TASK_STATS_ID", """Task scheduler statistics answer: n mavlink messages where n is the number of tasks""")
+MAV_ADA_ID = 6
+enums["SystemTMList"][6] = EnumEntry("MAV_ADA_ID", """ADA Status""")
+MAV_NAS_ID = 7
+enums["SystemTMList"][7] = EnumEntry("MAV_NAS_ID", """NavigationSystem data""")
+MAV_MEA_ID = 8
+enums["SystemTMList"][8] = EnumEntry("MAV_MEA_ID", """MEA Status""")
+MAV_CAN_STATS_ID = 9
+enums["SystemTMList"][9] = EnumEntry("MAV_CAN_STATS_ID", """Canbus stats""")
+MAV_FLIGHT_ID = 10
+enums["SystemTMList"][10] = EnumEntry("MAV_FLIGHT_ID", """Flight telemetry""")
+MAV_STATS_ID = 11
+enums["SystemTMList"][11] = EnumEntry("MAV_STATS_ID", """Satistics telemetry""")
+MAV_SENSORS_STATE_ID = 12
+enums["SystemTMList"][12] = EnumEntry("MAV_SENSORS_STATE_ID", """Sensors init state telemetry""")
+MAV_GSE_ID = 13
+enums["SystemTMList"][13] = EnumEntry("MAV_GSE_ID", """Ground Segnement Equipment""")
+MAV_MOTOR_ID = 14
+enums["SystemTMList"][14] = EnumEntry("MAV_MOTOR_ID", """Rocket Motor data""")
+MAV_REGISTRY_ID = 15
+enums["SystemTMList"][15] = EnumEntry("MAV_REGISTRY_ID", """Command to fetch all registry keys""")
+SystemTMList_ENUM_END = 16
+enums["SystemTMList"][16] = EnumEntry("SystemTMList_ENUM_END", """""")
 
 # SensorsTMList
-enums['SensorsTMList'] = {}
-MAV_BMX160_ID = 1 # BMX160 IMU data
-enums['SensorsTMList'][1] = EnumEntry('MAV_BMX160_ID', '''BMX160 IMU data''')
-MAV_VN100_ID = 2 # VN100 IMU data
-enums['SensorsTMList'][2] = EnumEntry('MAV_VN100_ID', '''VN100 IMU data''')
-MAV_MPU9250_ID = 3 # MPU9250 IMU data
-enums['SensorsTMList'][3] = EnumEntry('MAV_MPU9250_ID', '''MPU9250 IMU data''')
-MAV_ADS131M08_ID = 4 # ADS 8 channel ADC data
-enums['SensorsTMList'][4] = EnumEntry('MAV_ADS131M08_ID', '''ADS 8 channel ADC data''')
-MAV_MS5803_ID = 5 # MS5803 barometer data
-enums['SensorsTMList'][5] = EnumEntry('MAV_MS5803_ID', '''MS5803 barometer data''')
-MAV_BME280_ID = 6 # BME280 barometer data
-enums['SensorsTMList'][6] = EnumEntry('MAV_BME280_ID', '''BME280 barometer data''')
-MAV_LIS3MDL_ID = 7 # LIS3MDL compass data
-enums['SensorsTMList'][7] = EnumEntry('MAV_LIS3MDL_ID', '''LIS3MDL compass data''')
-MAV_LIS2MDL_ID = 8 # Magnetometer data
-enums['SensorsTMList'][8] = EnumEntry('MAV_LIS2MDL_ID', '''Magnetometer data''')
-MAV_LPS28DFW_ID = 9 # Pressure sensor data
-enums['SensorsTMList'][9] = EnumEntry('MAV_LPS28DFW_ID', '''Pressure sensor data''')
-MAV_LSM6DSRX_ID = 10 # IMU data
-enums['SensorsTMList'][10] = EnumEntry('MAV_LSM6DSRX_ID', '''IMU data''')
-MAV_H3LIS331DL_ID = 11 # 400G accelerometer
-enums['SensorsTMList'][11] = EnumEntry('MAV_H3LIS331DL_ID', '''400G accelerometer''')
-MAV_LPS22DF_ID = 12 # Pressure sensor data
-enums['SensorsTMList'][12] = EnumEntry('MAV_LPS22DF_ID', '''Pressure sensor data''')
-MAV_GPS_ID = 13 # GPS data
-enums['SensorsTMList'][13] = EnumEntry('MAV_GPS_ID', '''GPS data''')
-MAV_CURRENT_SENSE_ID = 14 # Electrical current sensors data
-enums['SensorsTMList'][14] = EnumEntry('MAV_CURRENT_SENSE_ID', '''Electrical current sensors data''')
-MAV_BATTERY_VOLTAGE_ID = 15 # Battery voltage data
-enums['SensorsTMList'][15] = EnumEntry('MAV_BATTERY_VOLTAGE_ID', '''Battery voltage data''')
-MAV_ROTATED_IMU_ID = 16 # Load cell data
-enums['SensorsTMList'][16] = EnumEntry('MAV_ROTATED_IMU_ID', '''Load cell data''')
-MAV_DPL_PRESS_ID = 17 # Deployment pressure data
-enums['SensorsTMList'][17] = EnumEntry('MAV_DPL_PRESS_ID', '''Deployment pressure data''')
-MAV_STATIC_PRESS_ID = 18 # Static pressure data
-enums['SensorsTMList'][18] = EnumEntry('MAV_STATIC_PRESS_ID', '''Static pressure data''')
-MAV_BACKUP_STATIC_PRESS_ID = 19 # Static pressure data
-enums['SensorsTMList'][19] = EnumEntry('MAV_BACKUP_STATIC_PRESS_ID', '''Static pressure data''')
-MAV_STATIC_PITOT_PRESS_ID = 20 # Pitot pressure data
-enums['SensorsTMList'][20] = EnumEntry('MAV_STATIC_PITOT_PRESS_ID', '''Pitot pressure data''')
-MAV_TOTAL_PITOT_PRESS_ID = 21 # Pitot pressure data
-enums['SensorsTMList'][21] = EnumEntry('MAV_TOTAL_PITOT_PRESS_ID', '''Pitot pressure data''')
-MAV_DYNAMIC_PITOT_PRESS_ID = 22 # Pitot pressure data
-enums['SensorsTMList'][22] = EnumEntry('MAV_DYNAMIC_PITOT_PRESS_ID', '''Pitot pressure data''')
-MAV_LOAD_CELL_ID = 23 # Load cell data
-enums['SensorsTMList'][23] = EnumEntry('MAV_LOAD_CELL_ID', '''Load cell data''')
-MAV_TANK_TOP_PRESS_ID = 24 # Top tank pressure
-enums['SensorsTMList'][24] = EnumEntry('MAV_TANK_TOP_PRESS_ID', '''Top tank pressure''')
-MAV_TANK_BOTTOM_PRESS_ID = 25 # Bottom tank pressure
-enums['SensorsTMList'][25] = EnumEntry('MAV_TANK_BOTTOM_PRESS_ID', '''Bottom tank pressure''')
-MAV_TANK_TEMP_ID = 26 # Tank temperature
-enums['SensorsTMList'][26] = EnumEntry('MAV_TANK_TEMP_ID', '''Tank temperature''')
-MAV_COMBUSTION_PRESS_ID = 27 # Combustion chamber pressure
-enums['SensorsTMList'][27] = EnumEntry('MAV_COMBUSTION_PRESS_ID', '''Combustion chamber pressure''')
-MAV_FILLING_PRESS_ID = 28 # Filling line pressure
-enums['SensorsTMList'][28] = EnumEntry('MAV_FILLING_PRESS_ID', '''Filling line pressure''')
-MAV_VESSEL_PRESS_ID = 29 # Vessel pressure
-enums['SensorsTMList'][29] = EnumEntry('MAV_VESSEL_PRESS_ID', '''Vessel pressure''')
-MAV_LOAD_CELL_VESSEL_ID = 30 # Vessel tank weight
-enums['SensorsTMList'][30] = EnumEntry('MAV_LOAD_CELL_VESSEL_ID', '''Vessel tank weight''')
-MAV_LOAD_CELL_TANK_ID = 31 # Tank weight
-enums['SensorsTMList'][31] = EnumEntry('MAV_LOAD_CELL_TANK_ID', '''Tank weight''')
-SensorsTMList_ENUM_END = 32 # 
-enums['SensorsTMList'][32] = EnumEntry('SensorsTMList_ENUM_END', '''''')
+enums["SensorsTMList"] = {}
+MAV_BMX160_ID = 1
+enums["SensorsTMList"][1] = EnumEntry("MAV_BMX160_ID", """BMX160 IMU data""")
+MAV_VN100_ID = 2
+enums["SensorsTMList"][2] = EnumEntry("MAV_VN100_ID", """VN100 IMU data""")
+MAV_MPU9250_ID = 3
+enums["SensorsTMList"][3] = EnumEntry("MAV_MPU9250_ID", """MPU9250 IMU data""")
+MAV_ADS131M08_ID = 4
+enums["SensorsTMList"][4] = EnumEntry("MAV_ADS131M08_ID", """ADS 8 channel ADC data""")
+MAV_MS5803_ID = 5
+enums["SensorsTMList"][5] = EnumEntry("MAV_MS5803_ID", """MS5803 barometer data""")
+MAV_BME280_ID = 6
+enums["SensorsTMList"][6] = EnumEntry("MAV_BME280_ID", """BME280 barometer data""")
+MAV_LIS3MDL_ID = 7
+enums["SensorsTMList"][7] = EnumEntry("MAV_LIS3MDL_ID", """LIS3MDL compass data""")
+MAV_LIS2MDL_ID = 8
+enums["SensorsTMList"][8] = EnumEntry("MAV_LIS2MDL_ID", """Magnetometer data""")
+MAV_LPS28DFW_ID = 9
+enums["SensorsTMList"][9] = EnumEntry("MAV_LPS28DFW_ID", """Pressure sensor data""")
+MAV_LSM6DSRX_ID = 10
+enums["SensorsTMList"][10] = EnumEntry("MAV_LSM6DSRX_ID", """IMU data""")
+MAV_H3LIS331DL_ID = 11
+enums["SensorsTMList"][11] = EnumEntry("MAV_H3LIS331DL_ID", """400G accelerometer""")
+MAV_LPS22DF_ID = 12
+enums["SensorsTMList"][12] = EnumEntry("MAV_LPS22DF_ID", """Pressure sensor data""")
+MAV_GPS_ID = 13
+enums["SensorsTMList"][13] = EnumEntry("MAV_GPS_ID", """GPS data""")
+MAV_CURRENT_SENSE_ID = 14
+enums["SensorsTMList"][14] = EnumEntry("MAV_CURRENT_SENSE_ID", """Electrical current sensors data""")
+MAV_BATTERY_VOLTAGE_ID = 15
+enums["SensorsTMList"][15] = EnumEntry("MAV_BATTERY_VOLTAGE_ID", """Battery voltage data""")
+MAV_ROTATED_IMU_ID = 16
+enums["SensorsTMList"][16] = EnumEntry("MAV_ROTATED_IMU_ID", """Load cell data""")
+MAV_DPL_PRESS_ID = 17
+enums["SensorsTMList"][17] = EnumEntry("MAV_DPL_PRESS_ID", """Deployment pressure data""")
+MAV_STATIC_PRESS_ID = 18
+enums["SensorsTMList"][18] = EnumEntry("MAV_STATIC_PRESS_ID", """Static pressure data""")
+MAV_BACKUP_STATIC_PRESS_ID = 19
+enums["SensorsTMList"][19] = EnumEntry("MAV_BACKUP_STATIC_PRESS_ID", """Static pressure data""")
+MAV_STATIC_PITOT_PRESS_ID = 20
+enums["SensorsTMList"][20] = EnumEntry("MAV_STATIC_PITOT_PRESS_ID", """Pitot pressure data""")
+MAV_TOTAL_PITOT_PRESS_ID = 21
+enums["SensorsTMList"][21] = EnumEntry("MAV_TOTAL_PITOT_PRESS_ID", """Pitot pressure data""")
+MAV_DYNAMIC_PITOT_PRESS_ID = 22
+enums["SensorsTMList"][22] = EnumEntry("MAV_DYNAMIC_PITOT_PRESS_ID", """Pitot pressure data""")
+MAV_LOAD_CELL_ID = 23
+enums["SensorsTMList"][23] = EnumEntry("MAV_LOAD_CELL_ID", """Load cell data""")
+MAV_TANK_TOP_PRESS_ID = 24
+enums["SensorsTMList"][24] = EnumEntry("MAV_TANK_TOP_PRESS_ID", """Top tank pressure""")
+MAV_TANK_BOTTOM_PRESS_ID = 25
+enums["SensorsTMList"][25] = EnumEntry("MAV_TANK_BOTTOM_PRESS_ID", """Bottom tank pressure""")
+MAV_TANK_TEMP_ID = 26
+enums["SensorsTMList"][26] = EnumEntry("MAV_TANK_TEMP_ID", """Tank temperature""")
+MAV_COMBUSTION_PRESS_ID = 27
+enums["SensorsTMList"][27] = EnumEntry("MAV_COMBUSTION_PRESS_ID", """Combustion chamber pressure""")
+MAV_FILLING_PRESS_ID = 28
+enums["SensorsTMList"][28] = EnumEntry("MAV_FILLING_PRESS_ID", """Filling line pressure""")
+MAV_VESSEL_PRESS_ID = 29
+enums["SensorsTMList"][29] = EnumEntry("MAV_VESSEL_PRESS_ID", """Vessel pressure""")
+MAV_LOAD_CELL_VESSEL_ID = 30
+enums["SensorsTMList"][30] = EnumEntry("MAV_LOAD_CELL_VESSEL_ID", """Vessel tank weight""")
+MAV_LOAD_CELL_TANK_ID = 31
+enums["SensorsTMList"][31] = EnumEntry("MAV_LOAD_CELL_TANK_ID", """Tank weight""")
+SensorsTMList_ENUM_END = 32
+enums["SensorsTMList"][32] = EnumEntry("SensorsTMList_ENUM_END", """""")
 
 # MavCommandList
-enums['MavCommandList'] = {}
-MAV_CMD_ARM = 1 # Command to arm the rocket
-enums['MavCommandList'][1] = EnumEntry('MAV_CMD_ARM', '''Command to arm the rocket''')
-MAV_CMD_DISARM = 2 # Command to disarm the rocket
-enums['MavCommandList'][2] = EnumEntry('MAV_CMD_DISARM', '''Command to disarm the rocket''')
-MAV_CMD_CALIBRATE = 3 # Command to trigger the calibration
-enums['MavCommandList'][3] = EnumEntry('MAV_CMD_CALIBRATE', '''Command to trigger the calibration''')
-MAV_CMD_SAVE_CALIBRATION = 4 # Command to save the current calibration into a file
-enums['MavCommandList'][4] = EnumEntry('MAV_CMD_SAVE_CALIBRATION', '''Command to save the current calibration into a file''')
-MAV_CMD_FORCE_INIT = 5 # Command to init the rocket
-enums['MavCommandList'][5] = EnumEntry('MAV_CMD_FORCE_INIT', '''Command to init the rocket''')
-MAV_CMD_FORCE_LAUNCH = 6 # Command to force the launch state on the rocket
-enums['MavCommandList'][6] = EnumEntry('MAV_CMD_FORCE_LAUNCH', '''Command to force the launch state on the rocket''')
-MAV_CMD_FORCE_ENGINE_SHUTDOWN = 7 # Command to trigger engine shutdown
-enums['MavCommandList'][7] = EnumEntry('MAV_CMD_FORCE_ENGINE_SHUTDOWN', '''Command to trigger engine shutdown''')
-MAV_CMD_FORCE_EXPULSION = 8 # Command to trigger nosecone expulsion
-enums['MavCommandList'][8] = EnumEntry('MAV_CMD_FORCE_EXPULSION', '''Command to trigger nosecone expulsion''')
-MAV_CMD_FORCE_DEPLOYMENT = 9 # Command to activate the thermal cutters and cut the drogue, activating
-                        # both thermal cutters sequentially
-enums['MavCommandList'][9] = EnumEntry('MAV_CMD_FORCE_DEPLOYMENT', '''Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially''')
-MAV_CMD_FORCE_LANDING = 10 # Command to communicate the end of the mission and close the file
-                        # descriptors in the SD card
-enums['MavCommandList'][10] = EnumEntry('MAV_CMD_FORCE_LANDING', '''Command to communicate the end of the mission and close the file descriptors in the SD card''')
-MAV_CMD_START_LOGGING = 11 # Command to enable sensor logging
-enums['MavCommandList'][11] = EnumEntry('MAV_CMD_START_LOGGING', '''Command to enable sensor logging''')
-MAV_CMD_STOP_LOGGING = 12 # Command to permanently close the log file
-enums['MavCommandList'][12] = EnumEntry('MAV_CMD_STOP_LOGGING', '''Command to permanently close the log file''')
-MAV_CMD_FORCE_REBOOT = 13 # Command to reset the board from test status
-enums['MavCommandList'][13] = EnumEntry('MAV_CMD_FORCE_REBOOT', '''Command to reset the board from test status''')
-MAV_CMD_ENTER_TEST_MODE = 14 # Command to enter the test mode
-enums['MavCommandList'][14] = EnumEntry('MAV_CMD_ENTER_TEST_MODE', '''Command to enter the test mode''')
-MAV_CMD_EXIT_TEST_MODE = 15 # Command to exit the test mode
-enums['MavCommandList'][15] = EnumEntry('MAV_CMD_EXIT_TEST_MODE', '''Command to exit the test mode''')
-MAV_CMD_START_RECORDING = 16 # Command to start the internal cameras recordings
-enums['MavCommandList'][16] = EnumEntry('MAV_CMD_START_RECORDING', '''Command to start the internal cameras recordings''')
-MAV_CMD_STOP_RECORDING = 17 # Command to stop the internal cameras recordings
-enums['MavCommandList'][17] = EnumEntry('MAV_CMD_STOP_RECORDING', '''Command to stop the internal cameras recordings''')
-MAV_CMD_OPEN_NITROGEN = 18 # Command to open the nitrogen valve
-enums['MavCommandList'][18] = EnumEntry('MAV_CMD_OPEN_NITROGEN', '''Command to open the nitrogen valve''')
-MAV_CMD_REGISTRY_LOAD = 19 # Command to reload the registry from memory
-enums['MavCommandList'][19] = EnumEntry('MAV_CMD_REGISTRY_LOAD', '''Command to reload the registry from memory''')
-MAV_CMD_REGISTRY_SAVE = 20 # Command to commit the registry to memory
-enums['MavCommandList'][20] = EnumEntry('MAV_CMD_REGISTRY_SAVE', '''Command to commit the registry to memory''')
-MAV_CMD_REGISTRY_CLEAR = 21 # Command to clear the registry
-enums['MavCommandList'][21] = EnumEntry('MAV_CMD_REGISTRY_CLEAR', '''Command to clear the registry''')
-MAV_CMD_ENTER_HIL = 22 # Command to enter HIL mode at next reboot
-enums['MavCommandList'][22] = EnumEntry('MAV_CMD_ENTER_HIL', '''Command to enter HIL mode at next reboot''')
-MavCommandList_ENUM_END = 23 # 
-enums['MavCommandList'][23] = EnumEntry('MavCommandList_ENUM_END', '''''')
+enums["MavCommandList"] = {}
+MAV_CMD_ARM = 1
+enums["MavCommandList"][1] = EnumEntry("MAV_CMD_ARM", """Command to arm the rocket""")
+MAV_CMD_DISARM = 2
+enums["MavCommandList"][2] = EnumEntry("MAV_CMD_DISARM", """Command to disarm the rocket""")
+MAV_CMD_CALIBRATE = 3
+enums["MavCommandList"][3] = EnumEntry("MAV_CMD_CALIBRATE", """Command to trigger the calibration""")
+MAV_CMD_SAVE_CALIBRATION = 4
+enums["MavCommandList"][4] = EnumEntry("MAV_CMD_SAVE_CALIBRATION", """Command to save the current calibration into a file""")
+MAV_CMD_FORCE_INIT = 5
+enums["MavCommandList"][5] = EnumEntry("MAV_CMD_FORCE_INIT", """Command to init the rocket""")
+MAV_CMD_FORCE_LAUNCH = 6
+enums["MavCommandList"][6] = EnumEntry("MAV_CMD_FORCE_LAUNCH", """Command to force the launch state on the rocket""")
+MAV_CMD_FORCE_ENGINE_SHUTDOWN = 7
+enums["MavCommandList"][7] = EnumEntry("MAV_CMD_FORCE_ENGINE_SHUTDOWN", """Command to trigger engine shutdown""")
+MAV_CMD_FORCE_EXPULSION = 8
+enums["MavCommandList"][8] = EnumEntry("MAV_CMD_FORCE_EXPULSION", """Command to trigger nosecone expulsion""")
+MAV_CMD_FORCE_DEPLOYMENT = 9
+enums["MavCommandList"][9] = EnumEntry("MAV_CMD_FORCE_DEPLOYMENT", """Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially""")
+MAV_CMD_FORCE_LANDING = 10
+enums["MavCommandList"][10] = EnumEntry("MAV_CMD_FORCE_LANDING", """Command to communicate the end of the mission and close the file descriptors in the SD card""")
+MAV_CMD_START_LOGGING = 11
+enums["MavCommandList"][11] = EnumEntry("MAV_CMD_START_LOGGING", """Command to enable sensor logging""")
+MAV_CMD_STOP_LOGGING = 12
+enums["MavCommandList"][12] = EnumEntry("MAV_CMD_STOP_LOGGING", """Command to permanently close the log file""")
+MAV_CMD_FORCE_REBOOT = 13
+enums["MavCommandList"][13] = EnumEntry("MAV_CMD_FORCE_REBOOT", """Command to reset the board from test status""")
+MAV_CMD_ENTER_TEST_MODE = 14
+enums["MavCommandList"][14] = EnumEntry("MAV_CMD_ENTER_TEST_MODE", """Command to enter the test mode""")
+MAV_CMD_EXIT_TEST_MODE = 15
+enums["MavCommandList"][15] = EnumEntry("MAV_CMD_EXIT_TEST_MODE", """Command to exit the test mode""")
+MAV_CMD_START_RECORDING = 16
+enums["MavCommandList"][16] = EnumEntry("MAV_CMD_START_RECORDING", """Command to start the internal cameras recordings""")
+MAV_CMD_STOP_RECORDING = 17
+enums["MavCommandList"][17] = EnumEntry("MAV_CMD_STOP_RECORDING", """Command to stop the internal cameras recordings""")
+MAV_CMD_OPEN_NITROGEN = 18
+enums["MavCommandList"][18] = EnumEntry("MAV_CMD_OPEN_NITROGEN", """Command to open the nitrogen valve""")
+MAV_CMD_REGISTRY_LOAD = 19
+enums["MavCommandList"][19] = EnumEntry("MAV_CMD_REGISTRY_LOAD", """Command to reload the registry from memory""")
+MAV_CMD_REGISTRY_SAVE = 20
+enums["MavCommandList"][20] = EnumEntry("MAV_CMD_REGISTRY_SAVE", """Command to commit the registry to memory""")
+MAV_CMD_REGISTRY_CLEAR = 21
+enums["MavCommandList"][21] = EnumEntry("MAV_CMD_REGISTRY_CLEAR", """Command to clear the registry""")
+MAV_CMD_ENTER_HIL = 22
+enums["MavCommandList"][22] = EnumEntry("MAV_CMD_ENTER_HIL", """Command to enter HIL mode at next reboot""")
+MavCommandList_ENUM_END = 23
+enums["MavCommandList"][23] = EnumEntry("MavCommandList_ENUM_END", """""")
+
+# MavArpCommandList
+enums["MavArpCommandList"] = {}
+MAV_ARP_CMD_FORCE_INIT = 1
+enums["MavArpCommandList"][1] = EnumEntry("MAV_ARP_CMD_FORCE_INIT", """Command to force the initialization of ARP""")
+MAV_ARP_CMD_RESET_ALGORITHM = 2
+enums["MavArpCommandList"][2] = EnumEntry("MAV_ARP_CMD_RESET_ALGORITHM", """Command to reset the algorithm""")
+MAV_ARP_CMD_RESET_BOARD = 3
+enums["MavArpCommandList"][3] = EnumEntry("MAV_ARP_CMD_RESET_BOARD", """Command to force a reboot""")
+MAV_ARP_CMD_FORCE_NO_FEEDBACK = 4
+enums["MavArpCommandList"][4] = EnumEntry("MAV_ARP_CMD_FORCE_NO_FEEDBACK", """Command to move ARP to the not-feedback mode""")
+MAV_ARP_CMD_ARM = 5
+enums["MavArpCommandList"][5] = EnumEntry("MAV_ARP_CMD_ARM", """Command to arm ARP""")
+MAV_ARP_CMD_DISARM = 6
+enums["MavArpCommandList"][6] = EnumEntry("MAV_ARP_CMD_DISARM", """Command to disarm ARP""")
+MAV_ARP_CMD_FOLLOW = 7
+enums["MavArpCommandList"][7] = EnumEntry("MAV_ARP_CMD_FOLLOW", """Command to start Follow loop of ARP""")
+MAV_ARP_CMD_CALIBRATE = 8
+enums["MavArpCommandList"][8] = EnumEntry("MAV_ARP_CMD_CALIBRATE", """Command to calibrate ARP""")
+MAV_ARP_CMD_ENTER_TEST_MODE = 9
+enums["MavArpCommandList"][9] = EnumEntry("MAV_ARP_CMD_ENTER_TEST_MODE", """Command to enter the test mode""")
+MAV_ARP_CMD_EXIT_TEST_MODE = 10
+enums["MavArpCommandList"][10] = EnumEntry("MAV_ARP_CMD_EXIT_TEST_MODE", """Command to exit the test mode""")
+MavArpCommandList_ENUM_END = 11
+enums["MavArpCommandList"][11] = EnumEntry("MavArpCommandList_ENUM_END", """""")
 
 # ServosList
-enums['ServosList'] = {}
-AIR_BRAKES_SERVO = 1 # 
-enums['ServosList'][1] = EnumEntry('AIR_BRAKES_SERVO', '''''')
-EXPULSION_SERVO = 2 # 
-enums['ServosList'][2] = EnumEntry('EXPULSION_SERVO', '''''')
-PARAFOIL_LEFT_SERVO = 3 # 
-enums['ServosList'][3] = EnumEntry('PARAFOIL_LEFT_SERVO', '''''')
-PARAFOIL_RIGHT_SERVO = 4 # 
-enums['ServosList'][4] = EnumEntry('PARAFOIL_RIGHT_SERVO', '''''')
-MAIN_VALVE = 5 # 
-enums['ServosList'][5] = EnumEntry('MAIN_VALVE', '''''')
-VENTING_VALVE = 6 # 
-enums['ServosList'][6] = EnumEntry('VENTING_VALVE', '''''')
-RELEASE_VALVE = 7 # 
-enums['ServosList'][7] = EnumEntry('RELEASE_VALVE', '''''')
-FILLING_VALVE = 8 # 
-enums['ServosList'][8] = EnumEntry('FILLING_VALVE', '''''')
-DISCONNECT_SERVO = 9 # 
-enums['ServosList'][9] = EnumEntry('DISCONNECT_SERVO', '''''')
-ServosList_ENUM_END = 10 # 
-enums['ServosList'][10] = EnumEntry('ServosList_ENUM_END', '''''')
+enums["ServosList"] = {}
+AIR_BRAKES_SERVO = 1
+enums["ServosList"][1] = EnumEntry("AIR_BRAKES_SERVO", """""")
+EXPULSION_SERVO = 2
+enums["ServosList"][2] = EnumEntry("EXPULSION_SERVO", """""")
+PARAFOIL_LEFT_SERVO = 3
+enums["ServosList"][3] = EnumEntry("PARAFOIL_LEFT_SERVO", """""")
+PARAFOIL_RIGHT_SERVO = 4
+enums["ServosList"][4] = EnumEntry("PARAFOIL_RIGHT_SERVO", """""")
+MAIN_VALVE = 5
+enums["ServosList"][5] = EnumEntry("MAIN_VALVE", """""")
+VENTING_VALVE = 6
+enums["ServosList"][6] = EnumEntry("VENTING_VALVE", """""")
+RELEASE_VALVE = 7
+enums["ServosList"][7] = EnumEntry("RELEASE_VALVE", """""")
+FILLING_VALVE = 8
+enums["ServosList"][8] = EnumEntry("FILLING_VALVE", """""")
+DISCONNECT_SERVO = 9
+enums["ServosList"][9] = EnumEntry("DISCONNECT_SERVO", """""")
+ServosList_ENUM_END = 10
+enums["ServosList"][10] = EnumEntry("ServosList_ENUM_END", """""")
 
 # StepperList
-enums['StepperList'] = {}
-STEPPER_X = 1 # 
-enums['StepperList'][1] = EnumEntry('STEPPER_X', '''''')
-STEPPER_Y = 2 # 
-enums['StepperList'][2] = EnumEntry('STEPPER_Y', '''''')
-StepperList_ENUM_END = 3 # 
-enums['StepperList'][3] = EnumEntry('StepperList_ENUM_END', '''''')
+enums["StepperList"] = {}
+STEPPER_X = 1
+enums["StepperList"][1] = EnumEntry("STEPPER_X", """""")
+STEPPER_Y = 2
+enums["StepperList"][2] = EnumEntry("STEPPER_Y", """""")
+StepperList_ENUM_END = 3
+enums["StepperList"][3] = EnumEntry("StepperList_ENUM_END", """""")
 
 # PinsList
-enums['PinsList'] = {}
-RAMP_PIN = 1 # 
-enums['PinsList'][1] = EnumEntry('RAMP_PIN', '''''')
-NOSECONE_PIN = 2 # 
-enums['PinsList'][2] = EnumEntry('NOSECONE_PIN', '''''')
-DEPLOYMENT_PIN = 3 # 
-enums['PinsList'][3] = EnumEntry('DEPLOYMENT_PIN', '''''')
-PinsList_ENUM_END = 4 # 
-enums['PinsList'][4] = EnumEntry('PinsList_ENUM_END', '''''')
+enums["PinsList"] = {}
+RAMP_PIN = 1
+enums["PinsList"][1] = EnumEntry("RAMP_PIN", """""")
+NOSECONE_PIN = 2
+enums["PinsList"][2] = EnumEntry("NOSECONE_PIN", """""")
+DEPLOYMENT_PIN = 3
+enums["PinsList"][3] = EnumEntry("DEPLOYMENT_PIN", """""")
+PinsList_ENUM_END = 4
+enums["PinsList"][4] = EnumEntry("PinsList_ENUM_END", """""")
 
 # message IDs
 MAVLINK_MSG_ID_BAD_DATA = -1
@@ -525,6 +611,7 @@ MAVLINK_MSG_ID_REGISTRY_COORD_TM = 117
 MAVLINK_MSG_ID_ARP_TM = 150
 MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC = 151
 MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC = 152
+MAVLINK_MSG_ID_ARP_COMMAND_TC = 172
 MAVLINK_MSG_ID_SYS_TM = 200
 MAVLINK_MSG_ID_LOGGER_TM = 201
 MAVLINK_MSG_ID_MAVLINK_STATS_TM = 202
@@ -540,4607 +627,5039 @@ MAVLINK_MSG_ID_PAYLOAD_STATS_TM = 211
 MAVLINK_MSG_ID_GSE_TM = 212
 MAVLINK_MSG_ID_MOTOR_TM = 213
 
+
 class MAVLink_ping_tc_message(MAVLink_message):
-        '''
-        TC to ping the rocket (expects an ACK message as a response)
-        '''
-        id = MAVLINK_MSG_ID_PING_TC
-        name = 'PING_TC'
-        fieldnames = ['timestamp']
-        ordered_fieldnames = ['timestamp']
-        fieldtypes = ['uint64_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<Q'
-        native_format = bytearray('<Q', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 136
-        unpacker = struct.Struct('<Q')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp):
-                MAVLink_message.__init__(self, MAVLink_ping_tc_message.id, MAVLink_ping_tc_message.name)
-                self._fieldnames = MAVLink_ping_tc_message.fieldnames
-                self._instance_field = MAVLink_ping_tc_message.instance_field
-                self._instance_offset = MAVLink_ping_tc_message.instance_offset
-                self.timestamp = timestamp
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 136, struct.pack('<Q', self.timestamp), force_mavlink1=force_mavlink1)
+    """
+    TC to ping the rocket (expects an ACK message as a response)
+    """
+
+    id = MAVLINK_MSG_ID_PING_TC
+    msgname = "PING_TC"
+    fieldnames = ["timestamp"]
+    ordered_fieldnames = ["timestamp"]
+    fieldtypes = ["uint64_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<Q")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 136
+    unpacker = struct.Struct("<Q")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int):
+        MAVLink_message.__init__(self, MAVLink_ping_tc_message.id, MAVLink_ping_tc_message.msgname)
+        self._fieldnames = MAVLink_ping_tc_message.fieldnames
+        self._instance_field = MAVLink_ping_tc_message.instance_field
+        self._instance_offset = MAVLink_ping_tc_message.instance_offset
+        self.timestamp = timestamp
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_ping_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_command_tc_message(MAVLink_message):
-        '''
-        TC containing a command with no parameters that trigger some
-        action
-        '''
-        id = MAVLINK_MSG_ID_COMMAND_TC
-        name = 'COMMAND_TC'
-        fieldnames = ['command_id']
-        ordered_fieldnames = ['command_id']
-        fieldtypes = ['uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<B'
-        native_format = bytearray('<B', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 198
-        unpacker = struct.Struct('<B')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, command_id):
-                MAVLink_message.__init__(self, MAVLink_command_tc_message.id, MAVLink_command_tc_message.name)
-                self._fieldnames = MAVLink_command_tc_message.fieldnames
-                self._instance_field = MAVLink_command_tc_message.instance_field
-                self._instance_offset = MAVLink_command_tc_message.instance_offset
-                self.command_id = command_id
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 198, struct.pack('<B', self.command_id), force_mavlink1=force_mavlink1)
+    """
+    TC containing a command with no parameters that trigger some
+    action
+    """
+
+    id = MAVLINK_MSG_ID_COMMAND_TC
+    msgname = "COMMAND_TC"
+    fieldnames = ["command_id"]
+    ordered_fieldnames = ["command_id"]
+    fieldtypes = ["uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<B")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 198
+    unpacker = struct.Struct("<B")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, command_id: int):
+        MAVLink_message.__init__(self, MAVLink_command_tc_message.id, MAVLink_command_tc_message.msgname)
+        self._fieldnames = MAVLink_command_tc_message.fieldnames
+        self._instance_field = MAVLink_command_tc_message.instance_field
+        self._instance_offset = MAVLink_command_tc_message.instance_offset
+        self.command_id = command_id
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.command_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_command_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_system_tm_request_tc_message(MAVLink_message):
-        '''
-        TC containing a request for the status of a board
-        '''
-        id = MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC
-        name = 'SYSTEM_TM_REQUEST_TC'
-        fieldnames = ['tm_id']
-        ordered_fieldnames = ['tm_id']
-        fieldtypes = ['uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<B'
-        native_format = bytearray('<B', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 165
-        unpacker = struct.Struct('<B')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, tm_id):
-                MAVLink_message.__init__(self, MAVLink_system_tm_request_tc_message.id, MAVLink_system_tm_request_tc_message.name)
-                self._fieldnames = MAVLink_system_tm_request_tc_message.fieldnames
-                self._instance_field = MAVLink_system_tm_request_tc_message.instance_field
-                self._instance_offset = MAVLink_system_tm_request_tc_message.instance_offset
-                self.tm_id = tm_id
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 165, struct.pack('<B', self.tm_id), force_mavlink1=force_mavlink1)
+    """
+    TC containing a request for the status of a board
+    """
+
+    id = MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC
+    msgname = "SYSTEM_TM_REQUEST_TC"
+    fieldnames = ["tm_id"]
+    ordered_fieldnames = ["tm_id"]
+    fieldtypes = ["uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<B")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 165
+    unpacker = struct.Struct("<B")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, tm_id: int):
+        MAVLink_message.__init__(self, MAVLink_system_tm_request_tc_message.id, MAVLink_system_tm_request_tc_message.msgname)
+        self._fieldnames = MAVLink_system_tm_request_tc_message.fieldnames
+        self._instance_field = MAVLink_system_tm_request_tc_message.instance_field
+        self._instance_offset = MAVLink_system_tm_request_tc_message.instance_offset
+        self.tm_id = tm_id
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.tm_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_system_tm_request_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_sensor_tm_request_tc_message(MAVLink_message):
-        '''
-        TC containing a request for sensors telemetry
-        '''
-        id = MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC
-        name = 'SENSOR_TM_REQUEST_TC'
-        fieldnames = ['sensor_name']
-        ordered_fieldnames = ['sensor_name']
-        fieldtypes = ['uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<B'
-        native_format = bytearray('<B', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 248
-        unpacker = struct.Struct('<B')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, sensor_name):
-                MAVLink_message.__init__(self, MAVLink_sensor_tm_request_tc_message.id, MAVLink_sensor_tm_request_tc_message.name)
-                self._fieldnames = MAVLink_sensor_tm_request_tc_message.fieldnames
-                self._instance_field = MAVLink_sensor_tm_request_tc_message.instance_field
-                self._instance_offset = MAVLink_sensor_tm_request_tc_message.instance_offset
-                self.sensor_name = sensor_name
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 248, struct.pack('<B', self.sensor_name), force_mavlink1=force_mavlink1)
+    """
+    TC containing a request for sensors telemetry
+    """
+
+    id = MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC
+    msgname = "SENSOR_TM_REQUEST_TC"
+    fieldnames = ["sensor_name"]
+    ordered_fieldnames = ["sensor_name"]
+    fieldtypes = ["uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<B")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 248
+    unpacker = struct.Struct("<B")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, sensor_name: int):
+        MAVLink_message.__init__(self, MAVLink_sensor_tm_request_tc_message.id, MAVLink_sensor_tm_request_tc_message.msgname)
+        self._fieldnames = MAVLink_sensor_tm_request_tc_message.fieldnames
+        self._instance_field = MAVLink_sensor_tm_request_tc_message.instance_field
+        self._instance_offset = MAVLink_sensor_tm_request_tc_message.instance_offset
+        self.sensor_name = sensor_name
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.sensor_name), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_sensor_tm_request_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_servo_tm_request_tc_message(MAVLink_message):
-        '''
-        TC containing a request for servo telemetry
-        '''
-        id = MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC
-        name = 'SERVO_TM_REQUEST_TC'
-        fieldnames = ['servo_id']
-        ordered_fieldnames = ['servo_id']
-        fieldtypes = ['uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<B'
-        native_format = bytearray('<B', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 184
-        unpacker = struct.Struct('<B')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, servo_id):
-                MAVLink_message.__init__(self, MAVLink_servo_tm_request_tc_message.id, MAVLink_servo_tm_request_tc_message.name)
-                self._fieldnames = MAVLink_servo_tm_request_tc_message.fieldnames
-                self._instance_field = MAVLink_servo_tm_request_tc_message.instance_field
-                self._instance_offset = MAVLink_servo_tm_request_tc_message.instance_offset
-                self.servo_id = servo_id
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 184, struct.pack('<B', self.servo_id), force_mavlink1=force_mavlink1)
+    """
+    TC containing a request for servo telemetry
+    """
+
+    id = MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC
+    msgname = "SERVO_TM_REQUEST_TC"
+    fieldnames = ["servo_id"]
+    ordered_fieldnames = ["servo_id"]
+    fieldtypes = ["uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<B")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 184
+    unpacker = struct.Struct("<B")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, servo_id: int):
+        MAVLink_message.__init__(self, MAVLink_servo_tm_request_tc_message.id, MAVLink_servo_tm_request_tc_message.msgname)
+        self._fieldnames = MAVLink_servo_tm_request_tc_message.fieldnames
+        self._instance_field = MAVLink_servo_tm_request_tc_message.instance_field
+        self._instance_offset = MAVLink_servo_tm_request_tc_message.instance_offset
+        self.servo_id = servo_id
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.servo_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_servo_tm_request_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_servo_angle_tc_message(MAVLink_message):
-        '''
-        Sets the angle of a certain servo
-        '''
-        id = MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC
-        name = 'SET_SERVO_ANGLE_TC'
-        fieldnames = ['servo_id', 'angle']
-        ordered_fieldnames = ['angle', 'servo_id']
-        fieldtypes = ['uint8_t', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<fB'
-        native_format = bytearray('<fB', 'ascii')
-        orders = [1, 0]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 215
-        unpacker = struct.Struct('<fB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, servo_id, angle):
-                MAVLink_message.__init__(self, MAVLink_set_servo_angle_tc_message.id, MAVLink_set_servo_angle_tc_message.name)
-                self._fieldnames = MAVLink_set_servo_angle_tc_message.fieldnames
-                self._instance_field = MAVLink_set_servo_angle_tc_message.instance_field
-                self._instance_offset = MAVLink_set_servo_angle_tc_message.instance_offset
-                self.servo_id = servo_id
-                self.angle = angle
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 215, struct.pack('<fB', self.angle, self.servo_id), force_mavlink1=force_mavlink1)
+    """
+    Sets the angle of a certain servo
+    """
+
+    id = MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC
+    msgname = "SET_SERVO_ANGLE_TC"
+    fieldnames = ["servo_id", "angle"]
+    ordered_fieldnames = ["angle", "servo_id"]
+    fieldtypes = ["uint8_t", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<fB")
+    orders = [1, 0]
+    lengths = [1, 1]
+    array_lengths = [0, 0]
+    crc_extra = 215
+    unpacker = struct.Struct("<fB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, servo_id: int, angle: float):
+        MAVLink_message.__init__(self, MAVLink_set_servo_angle_tc_message.id, MAVLink_set_servo_angle_tc_message.msgname)
+        self._fieldnames = MAVLink_set_servo_angle_tc_message.fieldnames
+        self._instance_field = MAVLink_set_servo_angle_tc_message.instance_field
+        self._instance_offset = MAVLink_set_servo_angle_tc_message.instance_offset
+        self.servo_id = servo_id
+        self.angle = angle
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.angle, self.servo_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_servo_angle_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_reset_servo_tc_message(MAVLink_message):
-        '''
-        Resets the specified servo
-        '''
-        id = MAVLINK_MSG_ID_RESET_SERVO_TC
-        name = 'RESET_SERVO_TC'
-        fieldnames = ['servo_id']
-        ordered_fieldnames = ['servo_id']
-        fieldtypes = ['uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<B'
-        native_format = bytearray('<B', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 226
-        unpacker = struct.Struct('<B')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, servo_id):
-                MAVLink_message.__init__(self, MAVLink_reset_servo_tc_message.id, MAVLink_reset_servo_tc_message.name)
-                self._fieldnames = MAVLink_reset_servo_tc_message.fieldnames
-                self._instance_field = MAVLink_reset_servo_tc_message.instance_field
-                self._instance_offset = MAVLink_reset_servo_tc_message.instance_offset
-                self.servo_id = servo_id
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 226, struct.pack('<B', self.servo_id), force_mavlink1=force_mavlink1)
+    """
+    Resets the specified servo
+    """
+
+    id = MAVLINK_MSG_ID_RESET_SERVO_TC
+    msgname = "RESET_SERVO_TC"
+    fieldnames = ["servo_id"]
+    ordered_fieldnames = ["servo_id"]
+    fieldtypes = ["uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<B")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 226
+    unpacker = struct.Struct("<B")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, servo_id: int):
+        MAVLink_message.__init__(self, MAVLink_reset_servo_tc_message.id, MAVLink_reset_servo_tc_message.msgname)
+        self._fieldnames = MAVLink_reset_servo_tc_message.fieldnames
+        self._instance_field = MAVLink_reset_servo_tc_message.instance_field
+        self._instance_offset = MAVLink_reset_servo_tc_message.instance_offset
+        self.servo_id = servo_id
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.servo_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_reset_servo_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_wiggle_servo_tc_message(MAVLink_message):
-        '''
-        Wiggles the specified servo
-        '''
-        id = MAVLINK_MSG_ID_WIGGLE_SERVO_TC
-        name = 'WIGGLE_SERVO_TC'
-        fieldnames = ['servo_id']
-        ordered_fieldnames = ['servo_id']
-        fieldtypes = ['uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<B'
-        native_format = bytearray('<B', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 160
-        unpacker = struct.Struct('<B')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, servo_id):
-                MAVLink_message.__init__(self, MAVLink_wiggle_servo_tc_message.id, MAVLink_wiggle_servo_tc_message.name)
-                self._fieldnames = MAVLink_wiggle_servo_tc_message.fieldnames
-                self._instance_field = MAVLink_wiggle_servo_tc_message.instance_field
-                self._instance_offset = MAVLink_wiggle_servo_tc_message.instance_offset
-                self.servo_id = servo_id
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 160, struct.pack('<B', self.servo_id), force_mavlink1=force_mavlink1)
+    """
+    Wiggles the specified servo
+    """
+
+    id = MAVLINK_MSG_ID_WIGGLE_SERVO_TC
+    msgname = "WIGGLE_SERVO_TC"
+    fieldnames = ["servo_id"]
+    ordered_fieldnames = ["servo_id"]
+    fieldtypes = ["uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<B")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 160
+    unpacker = struct.Struct("<B")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, servo_id: int):
+        MAVLink_message.__init__(self, MAVLink_wiggle_servo_tc_message.id, MAVLink_wiggle_servo_tc_message.msgname)
+        self._fieldnames = MAVLink_wiggle_servo_tc_message.fieldnames
+        self._instance_field = MAVLink_wiggle_servo_tc_message.instance_field
+        self._instance_offset = MAVLink_wiggle_servo_tc_message.instance_offset
+        self.servo_id = servo_id
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.servo_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_wiggle_servo_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_reference_altitude_tc_message(MAVLink_message):
-        '''
-        Sets the reference altitude for the altimeter
-        '''
-        id = MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC
-        name = 'SET_REFERENCE_ALTITUDE_TC'
-        fieldnames = ['ref_altitude']
-        ordered_fieldnames = ['ref_altitude']
-        fieldtypes = ['float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"ref_altitude": "m"}
-        format = '<f'
-        native_format = bytearray('<f', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 113
-        unpacker = struct.Struct('<f')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, ref_altitude):
-                MAVLink_message.__init__(self, MAVLink_set_reference_altitude_tc_message.id, MAVLink_set_reference_altitude_tc_message.name)
-                self._fieldnames = MAVLink_set_reference_altitude_tc_message.fieldnames
-                self._instance_field = MAVLink_set_reference_altitude_tc_message.instance_field
-                self._instance_offset = MAVLink_set_reference_altitude_tc_message.instance_offset
-                self.ref_altitude = ref_altitude
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 113, struct.pack('<f', self.ref_altitude), force_mavlink1=force_mavlink1)
+    """
+    Sets the reference altitude for the altimeter
+    """
+
+    id = MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC
+    msgname = "SET_REFERENCE_ALTITUDE_TC"
+    fieldnames = ["ref_altitude"]
+    ordered_fieldnames = ["ref_altitude"]
+    fieldtypes = ["float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"ref_altitude": "m"}
+    native_format = bytearray(b"<f")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 113
+    unpacker = struct.Struct("<f")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, ref_altitude: float):
+        MAVLink_message.__init__(self, MAVLink_set_reference_altitude_tc_message.id, MAVLink_set_reference_altitude_tc_message.msgname)
+        self._fieldnames = MAVLink_set_reference_altitude_tc_message.fieldnames
+        self._instance_field = MAVLink_set_reference_altitude_tc_message.instance_field
+        self._instance_offset = MAVLink_set_reference_altitude_tc_message.instance_offset
+        self.ref_altitude = ref_altitude
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.ref_altitude), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_reference_altitude_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_reference_temperature_tc_message(MAVLink_message):
-        '''
-        Sets the reference temperature for the altimeter
-        '''
-        id = MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC
-        name = 'SET_REFERENCE_TEMPERATURE_TC'
-        fieldnames = ['ref_temp']
-        ordered_fieldnames = ['ref_temp']
-        fieldtypes = ['float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"ref_temp": "degC"}
-        format = '<f'
-        native_format = bytearray('<f', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 38
-        unpacker = struct.Struct('<f')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, ref_temp):
-                MAVLink_message.__init__(self, MAVLink_set_reference_temperature_tc_message.id, MAVLink_set_reference_temperature_tc_message.name)
-                self._fieldnames = MAVLink_set_reference_temperature_tc_message.fieldnames
-                self._instance_field = MAVLink_set_reference_temperature_tc_message.instance_field
-                self._instance_offset = MAVLink_set_reference_temperature_tc_message.instance_offset
-                self.ref_temp = ref_temp
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 38, struct.pack('<f', self.ref_temp), force_mavlink1=force_mavlink1)
+    """
+    Sets the reference temperature for the altimeter
+    """
+
+    id = MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC
+    msgname = "SET_REFERENCE_TEMPERATURE_TC"
+    fieldnames = ["ref_temp"]
+    ordered_fieldnames = ["ref_temp"]
+    fieldtypes = ["float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"ref_temp": "degC"}
+    native_format = bytearray(b"<f")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 38
+    unpacker = struct.Struct("<f")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, ref_temp: float):
+        MAVLink_message.__init__(self, MAVLink_set_reference_temperature_tc_message.id, MAVLink_set_reference_temperature_tc_message.msgname)
+        self._fieldnames = MAVLink_set_reference_temperature_tc_message.fieldnames
+        self._instance_field = MAVLink_set_reference_temperature_tc_message.instance_field
+        self._instance_offset = MAVLink_set_reference_temperature_tc_message.instance_offset
+        self.ref_temp = ref_temp
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.ref_temp), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_reference_temperature_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_orientation_tc_message(MAVLink_message):
-        '''
-        Sets current orientation for the navigation system
-        '''
-        id = MAVLINK_MSG_ID_SET_ORIENTATION_TC
-        name = 'SET_ORIENTATION_TC'
-        fieldnames = ['yaw', 'pitch', 'roll']
-        ordered_fieldnames = ['yaw', 'pitch', 'roll']
-        fieldtypes = ['float', 'float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"yaw": "deg", "pitch": "deg", "roll": "deg"}
-        format = '<fff'
-        native_format = bytearray('<fff', 'ascii')
-        orders = [0, 1, 2]
-        lengths = [1, 1, 1]
-        array_lengths = [0, 0, 0]
-        crc_extra = 71
-        unpacker = struct.Struct('<fff')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, yaw, pitch, roll):
-                MAVLink_message.__init__(self, MAVLink_set_orientation_tc_message.id, MAVLink_set_orientation_tc_message.name)
-                self._fieldnames = MAVLink_set_orientation_tc_message.fieldnames
-                self._instance_field = MAVLink_set_orientation_tc_message.instance_field
-                self._instance_offset = MAVLink_set_orientation_tc_message.instance_offset
-                self.yaw = yaw
-                self.pitch = pitch
-                self.roll = roll
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 71, struct.pack('<fff', self.yaw, self.pitch, self.roll), force_mavlink1=force_mavlink1)
+    """
+    Sets current orientation for the navigation system
+    """
+
+    id = MAVLINK_MSG_ID_SET_ORIENTATION_TC
+    msgname = "SET_ORIENTATION_TC"
+    fieldnames = ["yaw", "pitch", "roll"]
+    ordered_fieldnames = ["yaw", "pitch", "roll"]
+    fieldtypes = ["float", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"yaw": "deg", "pitch": "deg", "roll": "deg"}
+    native_format = bytearray(b"<fff")
+    orders = [0, 1, 2]
+    lengths = [1, 1, 1]
+    array_lengths = [0, 0, 0]
+    crc_extra = 71
+    unpacker = struct.Struct("<fff")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, yaw: float, pitch: float, roll: float):
+        MAVLink_message.__init__(self, MAVLink_set_orientation_tc_message.id, MAVLink_set_orientation_tc_message.msgname)
+        self._fieldnames = MAVLink_set_orientation_tc_message.fieldnames
+        self._instance_field = MAVLink_set_orientation_tc_message.instance_field
+        self._instance_offset = MAVLink_set_orientation_tc_message.instance_offset
+        self.yaw = yaw
+        self.pitch = pitch
+        self.roll = roll
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.yaw, self.pitch, self.roll), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_orientation_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_orientation_quat_tc_message(MAVLink_message):
-        '''
-        Sets current orientation for the navigation system using a
-        quaternion
-        '''
-        id = MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC
-        name = 'SET_ORIENTATION_QUAT_TC'
-        fieldnames = ['quat_x', 'quat_y', 'quat_z', 'quat_w']
-        ordered_fieldnames = ['quat_x', 'quat_y', 'quat_z', 'quat_w']
-        fieldtypes = ['float', 'float', 'float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<ffff'
-        native_format = bytearray('<ffff', 'ascii')
-        orders = [0, 1, 2, 3]
-        lengths = [1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0]
-        crc_extra = 168
-        unpacker = struct.Struct('<ffff')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, quat_x, quat_y, quat_z, quat_w):
-                MAVLink_message.__init__(self, MAVLink_set_orientation_quat_tc_message.id, MAVLink_set_orientation_quat_tc_message.name)
-                self._fieldnames = MAVLink_set_orientation_quat_tc_message.fieldnames
-                self._instance_field = MAVLink_set_orientation_quat_tc_message.instance_field
-                self._instance_offset = MAVLink_set_orientation_quat_tc_message.instance_offset
-                self.quat_x = quat_x
-                self.quat_y = quat_y
-                self.quat_z = quat_z
-                self.quat_w = quat_w
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 168, struct.pack('<ffff', self.quat_x, self.quat_y, self.quat_z, self.quat_w), force_mavlink1=force_mavlink1)
+    """
+    Sets current orientation for the navigation system using a
+    quaternion
+    """
+
+    id = MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC
+    msgname = "SET_ORIENTATION_QUAT_TC"
+    fieldnames = ["quat_x", "quat_y", "quat_z", "quat_w"]
+    ordered_fieldnames = ["quat_x", "quat_y", "quat_z", "quat_w"]
+    fieldtypes = ["float", "float", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<ffff")
+    orders = [0, 1, 2, 3]
+    lengths = [1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0]
+    crc_extra = 168
+    unpacker = struct.Struct("<ffff")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, quat_x: float, quat_y: float, quat_z: float, quat_w: float):
+        MAVLink_message.__init__(self, MAVLink_set_orientation_quat_tc_message.id, MAVLink_set_orientation_quat_tc_message.msgname)
+        self._fieldnames = MAVLink_set_orientation_quat_tc_message.fieldnames
+        self._instance_field = MAVLink_set_orientation_quat_tc_message.instance_field
+        self._instance_offset = MAVLink_set_orientation_quat_tc_message.instance_offset
+        self.quat_x = quat_x
+        self.quat_y = quat_y
+        self.quat_z = quat_z
+        self.quat_w = quat_w
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.quat_x, self.quat_y, self.quat_z, self.quat_w), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_orientation_quat_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_coordinates_tc_message(MAVLink_message):
-        '''
-        Sets current coordinates
-        '''
-        id = MAVLINK_MSG_ID_SET_COORDINATES_TC
-        name = 'SET_COORDINATES_TC'
-        fieldnames = ['latitude', 'longitude']
-        ordered_fieldnames = ['latitude', 'longitude']
-        fieldtypes = ['float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"latitude": "deg", "longitude": "deg"}
-        format = '<ff'
-        native_format = bytearray('<ff', 'ascii')
-        orders = [0, 1]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 67
-        unpacker = struct.Struct('<ff')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, latitude, longitude):
-                MAVLink_message.__init__(self, MAVLink_set_coordinates_tc_message.id, MAVLink_set_coordinates_tc_message.name)
-                self._fieldnames = MAVLink_set_coordinates_tc_message.fieldnames
-                self._instance_field = MAVLink_set_coordinates_tc_message.instance_field
-                self._instance_offset = MAVLink_set_coordinates_tc_message.instance_offset
-                self.latitude = latitude
-                self.longitude = longitude
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 67, struct.pack('<ff', self.latitude, self.longitude), force_mavlink1=force_mavlink1)
+    """
+    Sets current coordinates
+    """
+
+    id = MAVLINK_MSG_ID_SET_COORDINATES_TC
+    msgname = "SET_COORDINATES_TC"
+    fieldnames = ["latitude", "longitude"]
+    ordered_fieldnames = ["latitude", "longitude"]
+    fieldtypes = ["float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"latitude": "deg", "longitude": "deg"}
+    native_format = bytearray(b"<ff")
+    orders = [0, 1]
+    lengths = [1, 1]
+    array_lengths = [0, 0]
+    crc_extra = 67
+    unpacker = struct.Struct("<ff")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, latitude: float, longitude: float):
+        MAVLink_message.__init__(self, MAVLink_set_coordinates_tc_message.id, MAVLink_set_coordinates_tc_message.msgname)
+        self._fieldnames = MAVLink_set_coordinates_tc_message.fieldnames
+        self._instance_field = MAVLink_set_coordinates_tc_message.instance_field
+        self._instance_offset = MAVLink_set_coordinates_tc_message.instance_offset
+        self.latitude = latitude
+        self.longitude = longitude
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.latitude, self.longitude), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_coordinates_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_raw_event_tc_message(MAVLink_message):
-        '''
-        TC containing a raw event to be posted directly in the
-        EventBroker
-        '''
-        id = MAVLINK_MSG_ID_RAW_EVENT_TC
-        name = 'RAW_EVENT_TC'
-        fieldnames = ['topic_id', 'event_id']
-        ordered_fieldnames = ['topic_id', 'event_id']
-        fieldtypes = ['uint8_t', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<BB'
-        native_format = bytearray('<BB', 'ascii')
-        orders = [0, 1]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 218
-        unpacker = struct.Struct('<BB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, topic_id, event_id):
-                MAVLink_message.__init__(self, MAVLink_raw_event_tc_message.id, MAVLink_raw_event_tc_message.name)
-                self._fieldnames = MAVLink_raw_event_tc_message.fieldnames
-                self._instance_field = MAVLink_raw_event_tc_message.instance_field
-                self._instance_offset = MAVLink_raw_event_tc_message.instance_offset
-                self.topic_id = topic_id
-                self.event_id = event_id
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 218, struct.pack('<BB', self.topic_id, self.event_id), force_mavlink1=force_mavlink1)
+    """
+    TC containing a raw event to be posted directly in the EventBroker
+    """
+
+    id = MAVLINK_MSG_ID_RAW_EVENT_TC
+    msgname = "RAW_EVENT_TC"
+    fieldnames = ["topic_id", "event_id"]
+    ordered_fieldnames = ["topic_id", "event_id"]
+    fieldtypes = ["uint8_t", "uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<BB")
+    orders = [0, 1]
+    lengths = [1, 1]
+    array_lengths = [0, 0]
+    crc_extra = 218
+    unpacker = struct.Struct("<BB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, topic_id: int, event_id: int):
+        MAVLink_message.__init__(self, MAVLink_raw_event_tc_message.id, MAVLink_raw_event_tc_message.msgname)
+        self._fieldnames = MAVLink_raw_event_tc_message.fieldnames
+        self._instance_field = MAVLink_raw_event_tc_message.instance_field
+        self._instance_offset = MAVLink_raw_event_tc_message.instance_offset
+        self.topic_id = topic_id
+        self.event_id = event_id
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.topic_id, self.event_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_raw_event_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_deployment_altitude_tc_message(MAVLink_message):
-        '''
-        Sets the deployment altitude for the main parachute
-        '''
-        id = MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC
-        name = 'SET_DEPLOYMENT_ALTITUDE_TC'
-        fieldnames = ['dpl_altitude']
-        ordered_fieldnames = ['dpl_altitude']
-        fieldtypes = ['float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"dpl_altitude": "m"}
-        format = '<f'
-        native_format = bytearray('<f', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 44
-        unpacker = struct.Struct('<f')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, dpl_altitude):
-                MAVLink_message.__init__(self, MAVLink_set_deployment_altitude_tc_message.id, MAVLink_set_deployment_altitude_tc_message.name)
-                self._fieldnames = MAVLink_set_deployment_altitude_tc_message.fieldnames
-                self._instance_field = MAVLink_set_deployment_altitude_tc_message.instance_field
-                self._instance_offset = MAVLink_set_deployment_altitude_tc_message.instance_offset
-                self.dpl_altitude = dpl_altitude
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 44, struct.pack('<f', self.dpl_altitude), force_mavlink1=force_mavlink1)
+    """
+    Sets the deployment altitude for the main parachute
+    """
+
+    id = MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC
+    msgname = "SET_DEPLOYMENT_ALTITUDE_TC"
+    fieldnames = ["dpl_altitude"]
+    ordered_fieldnames = ["dpl_altitude"]
+    fieldtypes = ["float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"dpl_altitude": "m"}
+    native_format = bytearray(b"<f")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 44
+    unpacker = struct.Struct("<f")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, dpl_altitude: float):
+        MAVLink_message.__init__(self, MAVLink_set_deployment_altitude_tc_message.id, MAVLink_set_deployment_altitude_tc_message.msgname)
+        self._fieldnames = MAVLink_set_deployment_altitude_tc_message.fieldnames
+        self._instance_field = MAVLink_set_deployment_altitude_tc_message.instance_field
+        self._instance_offset = MAVLink_set_deployment_altitude_tc_message.instance_offset
+        self.dpl_altitude = dpl_altitude
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.dpl_altitude), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_deployment_altitude_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_target_coordinates_tc_message(MAVLink_message):
-        '''
-        Sets the target coordinates
-        '''
-        id = MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC
-        name = 'SET_TARGET_COORDINATES_TC'
-        fieldnames = ['latitude', 'longitude']
-        ordered_fieldnames = ['latitude', 'longitude']
-        fieldtypes = ['float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"latitude": "deg", "longitude": "deg"}
-        format = '<ff'
-        native_format = bytearray('<ff', 'ascii')
-        orders = [0, 1]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 81
-        unpacker = struct.Struct('<ff')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, latitude, longitude):
-                MAVLink_message.__init__(self, MAVLink_set_target_coordinates_tc_message.id, MAVLink_set_target_coordinates_tc_message.name)
-                self._fieldnames = MAVLink_set_target_coordinates_tc_message.fieldnames
-                self._instance_field = MAVLink_set_target_coordinates_tc_message.instance_field
-                self._instance_offset = MAVLink_set_target_coordinates_tc_message.instance_offset
-                self.latitude = latitude
-                self.longitude = longitude
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 81, struct.pack('<ff', self.latitude, self.longitude), force_mavlink1=force_mavlink1)
+    """
+    Sets the target coordinates
+    """
+
+    id = MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC
+    msgname = "SET_TARGET_COORDINATES_TC"
+    fieldnames = ["latitude", "longitude"]
+    ordered_fieldnames = ["latitude", "longitude"]
+    fieldtypes = ["float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"latitude": "deg", "longitude": "deg"}
+    native_format = bytearray(b"<ff")
+    orders = [0, 1]
+    lengths = [1, 1]
+    array_lengths = [0, 0]
+    crc_extra = 81
+    unpacker = struct.Struct("<ff")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, latitude: float, longitude: float):
+        MAVLink_message.__init__(self, MAVLink_set_target_coordinates_tc_message.id, MAVLink_set_target_coordinates_tc_message.msgname)
+        self._fieldnames = MAVLink_set_target_coordinates_tc_message.fieldnames
+        self._instance_field = MAVLink_set_target_coordinates_tc_message.instance_field
+        self._instance_offset = MAVLink_set_target_coordinates_tc_message.instance_offset
+        self.latitude = latitude
+        self.longitude = longitude
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.latitude, self.longitude), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_target_coordinates_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_algorithm_tc_message(MAVLink_message):
-        '''
-        Sets the algorithm number (for parafoil guidance)
-        '''
-        id = MAVLINK_MSG_ID_SET_ALGORITHM_TC
-        name = 'SET_ALGORITHM_TC'
-        fieldnames = ['algorithm_number']
-        ordered_fieldnames = ['algorithm_number']
-        fieldtypes = ['uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<B'
-        native_format = bytearray('<B', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 181
-        unpacker = struct.Struct('<B')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, algorithm_number):
-                MAVLink_message.__init__(self, MAVLink_set_algorithm_tc_message.id, MAVLink_set_algorithm_tc_message.name)
-                self._fieldnames = MAVLink_set_algorithm_tc_message.fieldnames
-                self._instance_field = MAVLink_set_algorithm_tc_message.instance_field
-                self._instance_offset = MAVLink_set_algorithm_tc_message.instance_offset
-                self.algorithm_number = algorithm_number
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 181, struct.pack('<B', self.algorithm_number), force_mavlink1=force_mavlink1)
+    """
+    Sets the algorithm number (for parafoil guidance)
+    """
+
+    id = MAVLINK_MSG_ID_SET_ALGORITHM_TC
+    msgname = "SET_ALGORITHM_TC"
+    fieldnames = ["algorithm_number"]
+    ordered_fieldnames = ["algorithm_number"]
+    fieldtypes = ["uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<B")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 181
+    unpacker = struct.Struct("<B")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, algorithm_number: int):
+        MAVLink_message.__init__(self, MAVLink_set_algorithm_tc_message.id, MAVLink_set_algorithm_tc_message.msgname)
+        self._fieldnames = MAVLink_set_algorithm_tc_message.fieldnames
+        self._instance_field = MAVLink_set_algorithm_tc_message.instance_field
+        self._instance_offset = MAVLink_set_algorithm_tc_message.instance_offset
+        self.algorithm_number = algorithm_number
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.algorithm_number), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_algorithm_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_atomic_valve_timing_tc_message(MAVLink_message):
-        '''
-        Sets the maximum time that the valves can be open atomically
-        '''
-        id = MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC
-        name = 'SET_ATOMIC_VALVE_TIMING_TC'
-        fieldnames = ['servo_id', 'maximum_timing']
-        ordered_fieldnames = ['maximum_timing', 'servo_id']
-        fieldtypes = ['uint8_t', 'uint32_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"maximum_timing": "ms"}
-        format = '<IB'
-        native_format = bytearray('<IB', 'ascii')
-        orders = [1, 0]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 110
-        unpacker = struct.Struct('<IB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, servo_id, maximum_timing):
-                MAVLink_message.__init__(self, MAVLink_set_atomic_valve_timing_tc_message.id, MAVLink_set_atomic_valve_timing_tc_message.name)
-                self._fieldnames = MAVLink_set_atomic_valve_timing_tc_message.fieldnames
-                self._instance_field = MAVLink_set_atomic_valve_timing_tc_message.instance_field
-                self._instance_offset = MAVLink_set_atomic_valve_timing_tc_message.instance_offset
-                self.servo_id = servo_id
-                self.maximum_timing = maximum_timing
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 110, struct.pack('<IB', self.maximum_timing, self.servo_id), force_mavlink1=force_mavlink1)
+    """
+    Sets the maximum time that the valves can be open atomically
+    """
+
+    id = MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC
+    msgname = "SET_ATOMIC_VALVE_TIMING_TC"
+    fieldnames = ["servo_id", "maximum_timing"]
+    ordered_fieldnames = ["maximum_timing", "servo_id"]
+    fieldtypes = ["uint8_t", "uint32_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"maximum_timing": "ms"}
+    native_format = bytearray(b"<IB")
+    orders = [1, 0]
+    lengths = [1, 1]
+    array_lengths = [0, 0]
+    crc_extra = 110
+    unpacker = struct.Struct("<IB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, servo_id: int, maximum_timing: int):
+        MAVLink_message.__init__(self, MAVLink_set_atomic_valve_timing_tc_message.id, MAVLink_set_atomic_valve_timing_tc_message.msgname)
+        self._fieldnames = MAVLink_set_atomic_valve_timing_tc_message.fieldnames
+        self._instance_field = MAVLink_set_atomic_valve_timing_tc_message.instance_field
+        self._instance_offset = MAVLink_set_atomic_valve_timing_tc_message.instance_offset
+        self.servo_id = servo_id
+        self.maximum_timing = maximum_timing
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.maximum_timing, self.servo_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_atomic_valve_timing_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_valve_maximum_aperture_tc_message(MAVLink_message):
-        '''
-        Sets the maximum aperture of the specified valve. Set as value
-        from 0 to 1
-        '''
-        id = MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC
-        name = 'SET_VALVE_MAXIMUM_APERTURE_TC'
-        fieldnames = ['servo_id', 'maximum_aperture']
-        ordered_fieldnames = ['maximum_aperture', 'servo_id']
-        fieldtypes = ['uint8_t', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<fB'
-        native_format = bytearray('<fB', 'ascii')
-        orders = [1, 0]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 22
-        unpacker = struct.Struct('<fB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, servo_id, maximum_aperture):
-                MAVLink_message.__init__(self, MAVLink_set_valve_maximum_aperture_tc_message.id, MAVLink_set_valve_maximum_aperture_tc_message.name)
-                self._fieldnames = MAVLink_set_valve_maximum_aperture_tc_message.fieldnames
-                self._instance_field = MAVLink_set_valve_maximum_aperture_tc_message.instance_field
-                self._instance_offset = MAVLink_set_valve_maximum_aperture_tc_message.instance_offset
-                self.servo_id = servo_id
-                self.maximum_aperture = maximum_aperture
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 22, struct.pack('<fB', self.maximum_aperture, self.servo_id), force_mavlink1=force_mavlink1)
+    """
+    Sets the maximum aperture of the specified valve. Set as value
+    from 0 to 1
+    """
+
+    id = MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC
+    msgname = "SET_VALVE_MAXIMUM_APERTURE_TC"
+    fieldnames = ["servo_id", "maximum_aperture"]
+    ordered_fieldnames = ["maximum_aperture", "servo_id"]
+    fieldtypes = ["uint8_t", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<fB")
+    orders = [1, 0]
+    lengths = [1, 1]
+    array_lengths = [0, 0]
+    crc_extra = 22
+    unpacker = struct.Struct("<fB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, servo_id: int, maximum_aperture: float):
+        MAVLink_message.__init__(self, MAVLink_set_valve_maximum_aperture_tc_message.id, MAVLink_set_valve_maximum_aperture_tc_message.msgname)
+        self._fieldnames = MAVLink_set_valve_maximum_aperture_tc_message.fieldnames
+        self._instance_field = MAVLink_set_valve_maximum_aperture_tc_message.instance_field
+        self._instance_offset = MAVLink_set_valve_maximum_aperture_tc_message.instance_offset
+        self.servo_id = servo_id
+        self.maximum_aperture = maximum_aperture
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.maximum_aperture, self.servo_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_valve_maximum_aperture_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_conrig_state_tc_message(MAVLink_message):
-        '''
-        Send the state of the conrig buttons
-        '''
-        id = MAVLINK_MSG_ID_CONRIG_STATE_TC
-        name = 'CONRIG_STATE_TC'
-        fieldnames = ['ignition_btn', 'filling_valve_btn', 'venting_valve_btn', 'release_pressure_btn', 'quick_connector_btn', 'start_tars_btn', 'arm_switch']
-        ordered_fieldnames = ['ignition_btn', 'filling_valve_btn', 'venting_valve_btn', 'release_pressure_btn', 'quick_connector_btn', 'start_tars_btn', 'arm_switch']
-        fieldtypes = ['uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<BBBBBBB'
-        native_format = bytearray('<BBBBBBB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 5, 6]
-        lengths = [1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 65
-        unpacker = struct.Struct('<BBBBBBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, ignition_btn, filling_valve_btn, venting_valve_btn, release_pressure_btn, quick_connector_btn, start_tars_btn, arm_switch):
-                MAVLink_message.__init__(self, MAVLink_conrig_state_tc_message.id, MAVLink_conrig_state_tc_message.name)
-                self._fieldnames = MAVLink_conrig_state_tc_message.fieldnames
-                self._instance_field = MAVLink_conrig_state_tc_message.instance_field
-                self._instance_offset = MAVLink_conrig_state_tc_message.instance_offset
-                self.ignition_btn = ignition_btn
-                self.filling_valve_btn = filling_valve_btn
-                self.venting_valve_btn = venting_valve_btn
-                self.release_pressure_btn = release_pressure_btn
-                self.quick_connector_btn = quick_connector_btn
-                self.start_tars_btn = start_tars_btn
-                self.arm_switch = arm_switch
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 65, struct.pack('<BBBBBBB', self.ignition_btn, self.filling_valve_btn, self.venting_valve_btn, self.release_pressure_btn, self.quick_connector_btn, self.start_tars_btn, self.arm_switch), force_mavlink1=force_mavlink1)
+    """
+    Send the state of the conrig buttons
+    """
+
+    id = MAVLINK_MSG_ID_CONRIG_STATE_TC
+    msgname = "CONRIG_STATE_TC"
+    fieldnames = ["ignition_btn", "filling_valve_btn", "venting_valve_btn", "release_pressure_btn", "quick_connector_btn", "start_tars_btn", "arm_switch"]
+    ordered_fieldnames = ["ignition_btn", "filling_valve_btn", "venting_valve_btn", "release_pressure_btn", "quick_connector_btn", "start_tars_btn", "arm_switch"]
+    fieldtypes = ["uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<BBBBBBB")
+    orders = [0, 1, 2, 3, 4, 5, 6]
+    lengths = [1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0]
+    crc_extra = 65
+    unpacker = struct.Struct("<BBBBBBB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, ignition_btn: int, filling_valve_btn: int, venting_valve_btn: int, release_pressure_btn: int, quick_connector_btn: int, start_tars_btn: int, arm_switch: int):
+        MAVLink_message.__init__(self, MAVLink_conrig_state_tc_message.id, MAVLink_conrig_state_tc_message.msgname)
+        self._fieldnames = MAVLink_conrig_state_tc_message.fieldnames
+        self._instance_field = MAVLink_conrig_state_tc_message.instance_field
+        self._instance_offset = MAVLink_conrig_state_tc_message.instance_offset
+        self.ignition_btn = ignition_btn
+        self.filling_valve_btn = filling_valve_btn
+        self.venting_valve_btn = venting_valve_btn
+        self.release_pressure_btn = release_pressure_btn
+        self.quick_connector_btn = quick_connector_btn
+        self.start_tars_btn = start_tars_btn
+        self.arm_switch = arm_switch
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.ignition_btn, self.filling_valve_btn, self.venting_valve_btn, self.release_pressure_btn, self.quick_connector_btn, self.start_tars_btn, self.arm_switch), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_conrig_state_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_ignition_time_tc_message(MAVLink_message):
-        '''
-        Sets the time in ms that the igniter stays on before the
-        oxidant valve is opened
-        '''
-        id = MAVLINK_MSG_ID_SET_IGNITION_TIME_TC
-        name = 'SET_IGNITION_TIME_TC'
-        fieldnames = ['timing']
-        ordered_fieldnames = ['timing']
-        fieldtypes = ['uint32_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timing": "ms"}
-        format = '<I'
-        native_format = bytearray('<I', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 79
-        unpacker = struct.Struct('<I')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timing):
-                MAVLink_message.__init__(self, MAVLink_set_ignition_time_tc_message.id, MAVLink_set_ignition_time_tc_message.name)
-                self._fieldnames = MAVLink_set_ignition_time_tc_message.fieldnames
-                self._instance_field = MAVLink_set_ignition_time_tc_message.instance_field
-                self._instance_offset = MAVLink_set_ignition_time_tc_message.instance_offset
-                self.timing = timing
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 79, struct.pack('<I', self.timing), force_mavlink1=force_mavlink1)
+    """
+    Sets the time in ms that the igniter stays on before the oxidant
+    valve is opened
+    """
+
+    id = MAVLINK_MSG_ID_SET_IGNITION_TIME_TC
+    msgname = "SET_IGNITION_TIME_TC"
+    fieldnames = ["timing"]
+    ordered_fieldnames = ["timing"]
+    fieldtypes = ["uint32_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timing": "ms"}
+    native_format = bytearray(b"<I")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 79
+    unpacker = struct.Struct("<I")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timing: int):
+        MAVLink_message.__init__(self, MAVLink_set_ignition_time_tc_message.id, MAVLink_set_ignition_time_tc_message.msgname)
+        self._fieldnames = MAVLink_set_ignition_time_tc_message.fieldnames
+        self._instance_field = MAVLink_set_ignition_time_tc_message.instance_field
+        self._instance_offset = MAVLink_set_ignition_time_tc_message.instance_offset
+        self.timing = timing
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timing), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_ignition_time_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_nitrogen_time_tc_message(MAVLink_message):
-        '''
-        Sets the time in ms that the nitrogen will stay open
-        '''
-        id = MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC
-        name = 'SET_NITROGEN_TIME_TC'
-        fieldnames = ['timing']
-        ordered_fieldnames = ['timing']
-        fieldtypes = ['uint32_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timing": "ms"}
-        format = '<I'
-        native_format = bytearray('<I', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 167
-        unpacker = struct.Struct('<I')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timing):
-                MAVLink_message.__init__(self, MAVLink_set_nitrogen_time_tc_message.id, MAVLink_set_nitrogen_time_tc_message.name)
-                self._fieldnames = MAVLink_set_nitrogen_time_tc_message.fieldnames
-                self._instance_field = MAVLink_set_nitrogen_time_tc_message.instance_field
-                self._instance_offset = MAVLink_set_nitrogen_time_tc_message.instance_offset
-                self.timing = timing
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 167, struct.pack('<I', self.timing), force_mavlink1=force_mavlink1)
+    """
+    Sets the time in ms that the nitrogen will stay open
+    """
+
+    id = MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC
+    msgname = "SET_NITROGEN_TIME_TC"
+    fieldnames = ["timing"]
+    ordered_fieldnames = ["timing"]
+    fieldtypes = ["uint32_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timing": "ms"}
+    native_format = bytearray(b"<I")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 167
+    unpacker = struct.Struct("<I")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timing: int):
+        MAVLink_message.__init__(self, MAVLink_set_nitrogen_time_tc_message.id, MAVLink_set_nitrogen_time_tc_message.msgname)
+        self._fieldnames = MAVLink_set_nitrogen_time_tc_message.fieldnames
+        self._instance_field = MAVLink_set_nitrogen_time_tc_message.instance_field
+        self._instance_offset = MAVLink_set_nitrogen_time_tc_message.instance_offset
+        self.timing = timing
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timing), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_nitrogen_time_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_cooling_time_tc_message(MAVLink_message):
-        '''
-        Sets the time in ms that the system will wait before disarming
-        after firing
-        '''
-        id = MAVLINK_MSG_ID_SET_COOLING_TIME_TC
-        name = 'SET_COOLING_TIME_TC'
-        fieldnames = ['timing']
-        ordered_fieldnames = ['timing']
-        fieldtypes = ['uint32_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timing": "ms"}
-        format = '<I'
-        native_format = bytearray('<I', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 84
-        unpacker = struct.Struct('<I')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timing):
-                MAVLink_message.__init__(self, MAVLink_set_cooling_time_tc_message.id, MAVLink_set_cooling_time_tc_message.name)
-                self._fieldnames = MAVLink_set_cooling_time_tc_message.fieldnames
-                self._instance_field = MAVLink_set_cooling_time_tc_message.instance_field
-                self._instance_offset = MAVLink_set_cooling_time_tc_message.instance_offset
-                self.timing = timing
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 84, struct.pack('<I', self.timing), force_mavlink1=force_mavlink1)
+    """
+    Sets the time in ms that the system will wait before disarming
+    after firing
+    """
+
+    id = MAVLINK_MSG_ID_SET_COOLING_TIME_TC
+    msgname = "SET_COOLING_TIME_TC"
+    fieldnames = ["timing"]
+    ordered_fieldnames = ["timing"]
+    fieldtypes = ["uint32_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timing": "ms"}
+    native_format = bytearray(b"<I")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 84
+    unpacker = struct.Struct("<I")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timing: int):
+        MAVLink_message.__init__(self, MAVLink_set_cooling_time_tc_message.id, MAVLink_set_cooling_time_tc_message.msgname)
+        self._fieldnames = MAVLink_set_cooling_time_tc_message.fieldnames
+        self._instance_field = MAVLink_set_cooling_time_tc_message.instance_field
+        self._instance_offset = MAVLink_set_cooling_time_tc_message.instance_offset
+        self.timing = timing
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timing), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_cooling_time_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_stepper_angle_tc_message(MAVLink_message):
-        '''
-        Move the stepper of a certain angle
-        '''
-        id = MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC
-        name = 'SET_STEPPER_ANGLE_TC'
-        fieldnames = ['stepper_id', 'angle']
-        ordered_fieldnames = ['angle', 'stepper_id']
-        fieldtypes = ['uint8_t', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<fB'
-        native_format = bytearray('<fB', 'ascii')
-        orders = [1, 0]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 180
-        unpacker = struct.Struct('<fB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, stepper_id, angle):
-                MAVLink_message.__init__(self, MAVLink_set_stepper_angle_tc_message.id, MAVLink_set_stepper_angle_tc_message.name)
-                self._fieldnames = MAVLink_set_stepper_angle_tc_message.fieldnames
-                self._instance_field = MAVLink_set_stepper_angle_tc_message.instance_field
-                self._instance_offset = MAVLink_set_stepper_angle_tc_message.instance_offset
-                self.stepper_id = stepper_id
-                self.angle = angle
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 180, struct.pack('<fB', self.angle, self.stepper_id), force_mavlink1=force_mavlink1)
+    """
+    Move the stepper of a certain angle
+    """
+
+    id = MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC
+    msgname = "SET_STEPPER_ANGLE_TC"
+    fieldnames = ["stepper_id", "angle"]
+    ordered_fieldnames = ["angle", "stepper_id"]
+    fieldtypes = ["uint8_t", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<fB")
+    orders = [1, 0]
+    lengths = [1, 1]
+    array_lengths = [0, 0]
+    crc_extra = 180
+    unpacker = struct.Struct("<fB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, stepper_id: int, angle: float):
+        MAVLink_message.__init__(self, MAVLink_set_stepper_angle_tc_message.id, MAVLink_set_stepper_angle_tc_message.msgname)
+        self._fieldnames = MAVLink_set_stepper_angle_tc_message.fieldnames
+        self._instance_field = MAVLink_set_stepper_angle_tc_message.instance_field
+        self._instance_offset = MAVLink_set_stepper_angle_tc_message.instance_offset
+        self.stepper_id = stepper_id
+        self.angle = angle
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.angle, self.stepper_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_stepper_angle_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_stepper_steps_tc_message(MAVLink_message):
-        '''
-        Move the stepper of a certain amount of steps
-        '''
-        id = MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC
-        name = 'SET_STEPPER_STEPS_TC'
-        fieldnames = ['stepper_id', 'steps']
-        ordered_fieldnames = ['steps', 'stepper_id']
-        fieldtypes = ['uint8_t', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<fB'
-        native_format = bytearray('<fB', 'ascii')
-        orders = [1, 0]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 246
-        unpacker = struct.Struct('<fB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, stepper_id, steps):
-                MAVLink_message.__init__(self, MAVLink_set_stepper_steps_tc_message.id, MAVLink_set_stepper_steps_tc_message.name)
-                self._fieldnames = MAVLink_set_stepper_steps_tc_message.fieldnames
-                self._instance_field = MAVLink_set_stepper_steps_tc_message.instance_field
-                self._instance_offset = MAVLink_set_stepper_steps_tc_message.instance_offset
-                self.stepper_id = stepper_id
-                self.steps = steps
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 246, struct.pack('<fB', self.steps, self.stepper_id), force_mavlink1=force_mavlink1)
+    """
+    Move the stepper of a certain amount of steps
+    """
+
+    id = MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC
+    msgname = "SET_STEPPER_STEPS_TC"
+    fieldnames = ["stepper_id", "steps"]
+    ordered_fieldnames = ["steps", "stepper_id"]
+    fieldtypes = ["uint8_t", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<fB")
+    orders = [1, 0]
+    lengths = [1, 1]
+    array_lengths = [0, 0]
+    crc_extra = 246
+    unpacker = struct.Struct("<fB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, stepper_id: int, steps: float):
+        MAVLink_message.__init__(self, MAVLink_set_stepper_steps_tc_message.id, MAVLink_set_stepper_steps_tc_message.msgname)
+        self._fieldnames = MAVLink_set_stepper_steps_tc_message.fieldnames
+        self._instance_field = MAVLink_set_stepper_steps_tc_message.instance_field
+        self._instance_offset = MAVLink_set_stepper_steps_tc_message.instance_offset
+        self.stepper_id = stepper_id
+        self.steps = steps
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.steps, self.stepper_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_stepper_steps_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_ack_tm_message(MAVLink_message):
-        '''
-        TM containing an ACK message to notify that the message has
-        been processed correctly
-        '''
-        id = MAVLINK_MSG_ID_ACK_TM
-        name = 'ACK_TM'
-        fieldnames = ['recv_msgid', 'seq_ack']
-        ordered_fieldnames = ['recv_msgid', 'seq_ack']
-        fieldtypes = ['uint8_t', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<BB'
-        native_format = bytearray('<BB', 'ascii')
-        orders = [0, 1]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 50
-        unpacker = struct.Struct('<BB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, recv_msgid, seq_ack):
-                MAVLink_message.__init__(self, MAVLink_ack_tm_message.id, MAVLink_ack_tm_message.name)
-                self._fieldnames = MAVLink_ack_tm_message.fieldnames
-                self._instance_field = MAVLink_ack_tm_message.instance_field
-                self._instance_offset = MAVLink_ack_tm_message.instance_offset
-                self.recv_msgid = recv_msgid
-                self.seq_ack = seq_ack
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 50, struct.pack('<BB', self.recv_msgid, self.seq_ack), force_mavlink1=force_mavlink1)
+    """
+    TM containing an ACK message to notify that the message has been
+    processed correctly
+    """
+
+    id = MAVLINK_MSG_ID_ACK_TM
+    msgname = "ACK_TM"
+    fieldnames = ["recv_msgid", "seq_ack"]
+    ordered_fieldnames = ["recv_msgid", "seq_ack"]
+    fieldtypes = ["uint8_t", "uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<BB")
+    orders = [0, 1]
+    lengths = [1, 1]
+    array_lengths = [0, 0]
+    crc_extra = 50
+    unpacker = struct.Struct("<BB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, recv_msgid: int, seq_ack: int):
+        MAVLink_message.__init__(self, MAVLink_ack_tm_message.id, MAVLink_ack_tm_message.msgname)
+        self._fieldnames = MAVLink_ack_tm_message.fieldnames
+        self._instance_field = MAVLink_ack_tm_message.instance_field
+        self._instance_offset = MAVLink_ack_tm_message.instance_offset
+        self.recv_msgid = recv_msgid
+        self.seq_ack = seq_ack
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.recv_msgid, self.seq_ack), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_ack_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_nack_tm_message(MAVLink_message):
-        '''
-        TM containing a NACK message to notify that the received
-        message was invalid
-        '''
-        id = MAVLINK_MSG_ID_NACK_TM
-        name = 'NACK_TM'
-        fieldnames = ['recv_msgid', 'seq_ack', 'err_id']
-        ordered_fieldnames = ['err_id', 'recv_msgid', 'seq_ack']
-        fieldtypes = ['uint8_t', 'uint8_t', 'uint16_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<HBB'
-        native_format = bytearray('<HBB', 'ascii')
-        orders = [1, 2, 0]
-        lengths = [1, 1, 1]
-        array_lengths = [0, 0, 0]
-        crc_extra = 251
-        unpacker = struct.Struct('<HBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, recv_msgid, seq_ack, err_id):
-                MAVLink_message.__init__(self, MAVLink_nack_tm_message.id, MAVLink_nack_tm_message.name)
-                self._fieldnames = MAVLink_nack_tm_message.fieldnames
-                self._instance_field = MAVLink_nack_tm_message.instance_field
-                self._instance_offset = MAVLink_nack_tm_message.instance_offset
-                self.recv_msgid = recv_msgid
-                self.seq_ack = seq_ack
-                self.err_id = err_id
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 251, struct.pack('<HBB', self.err_id, self.recv_msgid, self.seq_ack), force_mavlink1=force_mavlink1)
+    """
+    TM containing a NACK message to notify that the received message
+    was invalid
+    """
+
+    id = MAVLINK_MSG_ID_NACK_TM
+    msgname = "NACK_TM"
+    fieldnames = ["recv_msgid", "seq_ack", "err_id"]
+    ordered_fieldnames = ["err_id", "recv_msgid", "seq_ack"]
+    fieldtypes = ["uint8_t", "uint8_t", "uint16_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<HBB")
+    orders = [1, 2, 0]
+    lengths = [1, 1, 1]
+    array_lengths = [0, 0, 0]
+    crc_extra = 251
+    unpacker = struct.Struct("<HBB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, recv_msgid: int, seq_ack: int, err_id: int):
+        MAVLink_message.__init__(self, MAVLink_nack_tm_message.id, MAVLink_nack_tm_message.msgname)
+        self._fieldnames = MAVLink_nack_tm_message.fieldnames
+        self._instance_field = MAVLink_nack_tm_message.instance_field
+        self._instance_offset = MAVLink_nack_tm_message.instance_offset
+        self.recv_msgid = recv_msgid
+        self.seq_ack = seq_ack
+        self.err_id = err_id
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.err_id, self.recv_msgid, self.seq_ack), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_nack_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_wack_tm_message(MAVLink_message):
-        '''
-        TM containing an ACK message to notify that the message has
-        been processed with a warning
-        '''
-        id = MAVLINK_MSG_ID_WACK_TM
-        name = 'WACK_TM'
-        fieldnames = ['recv_msgid', 'seq_ack', 'err_id']
-        ordered_fieldnames = ['err_id', 'recv_msgid', 'seq_ack']
-        fieldtypes = ['uint8_t', 'uint8_t', 'uint16_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<HBB'
-        native_format = bytearray('<HBB', 'ascii')
-        orders = [1, 2, 0]
-        lengths = [1, 1, 1]
-        array_lengths = [0, 0, 0]
-        crc_extra = 51
-        unpacker = struct.Struct('<HBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, recv_msgid, seq_ack, err_id):
-                MAVLink_message.__init__(self, MAVLink_wack_tm_message.id, MAVLink_wack_tm_message.name)
-                self._fieldnames = MAVLink_wack_tm_message.fieldnames
-                self._instance_field = MAVLink_wack_tm_message.instance_field
-                self._instance_offset = MAVLink_wack_tm_message.instance_offset
-                self.recv_msgid = recv_msgid
-                self.seq_ack = seq_ack
-                self.err_id = err_id
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 51, struct.pack('<HBB', self.err_id, self.recv_msgid, self.seq_ack), force_mavlink1=force_mavlink1)
+    """
+    TM containing an ACK message to notify that the message has been
+    processed with a warning
+    """
+
+    id = MAVLINK_MSG_ID_WACK_TM
+    msgname = "WACK_TM"
+    fieldnames = ["recv_msgid", "seq_ack", "err_id"]
+    ordered_fieldnames = ["err_id", "recv_msgid", "seq_ack"]
+    fieldtypes = ["uint8_t", "uint8_t", "uint16_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<HBB")
+    orders = [1, 2, 0]
+    lengths = [1, 1, 1]
+    array_lengths = [0, 0, 0]
+    crc_extra = 51
+    unpacker = struct.Struct("<HBB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, recv_msgid: int, seq_ack: int, err_id: int):
+        MAVLink_message.__init__(self, MAVLink_wack_tm_message.id, MAVLink_wack_tm_message.msgname)
+        self._fieldnames = MAVLink_wack_tm_message.fieldnames
+        self._instance_field = MAVLink_wack_tm_message.instance_field
+        self._instance_offset = MAVLink_wack_tm_message.instance_offset
+        self.recv_msgid = recv_msgid
+        self.seq_ack = seq_ack
+        self.err_id = err_id
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.err_id, self.recv_msgid, self.seq_ack), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_wack_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_gps_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_GPS_TM
-        name = 'GPS_TM'
-        fieldnames = ['timestamp', 'sensor_name', 'fix', 'latitude', 'longitude', 'height', 'vel_north', 'vel_east', 'vel_down', 'speed', 'track', 'n_satellites']
-        ordered_fieldnames = ['timestamp', 'latitude', 'longitude', 'height', 'vel_north', 'vel_east', 'vel_down', 'speed', 'track', 'sensor_name', 'fix', 'n_satellites']
-        fieldtypes = ['uint64_t', 'char', 'uint8_t', 'double', 'double', 'double', 'float', 'float', 'float', 'float', 'float', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "latitude": "deg", "longitude": "deg", "height": "m", "vel_north": "m/s", "vel_east": "m/s", "vel_down": "m/s", "speed": "m/s", "track": "deg"}
-        format = '<Qdddfffff20sBB'
-        native_format = bytearray('<QdddfffffcBB', 'ascii')
-        orders = [0, 9, 10, 1, 2, 3, 4, 5, 6, 7, 8, 11]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 0, 0]
-        crc_extra = 57
-        unpacker = struct.Struct('<Qdddfffff20sBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites):
-                MAVLink_message.__init__(self, MAVLink_gps_tm_message.id, MAVLink_gps_tm_message.name)
-                self._fieldnames = MAVLink_gps_tm_message.fieldnames
-                self._instance_field = MAVLink_gps_tm_message.instance_field
-                self._instance_offset = MAVLink_gps_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.sensor_name = sensor_name
-                self.fix = fix
-                self.latitude = latitude
-                self.longitude = longitude
-                self.height = height
-                self.vel_north = vel_north
-                self.vel_east = vel_east
-                self.vel_down = vel_down
-                self.speed = speed
-                self.track = track
-                self.n_satellites = n_satellites
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 57, struct.pack('<Qdddfffff20sBB', self.timestamp, self.latitude, self.longitude, self.height, self.vel_north, self.vel_east, self.vel_down, self.speed, self.track, self.sensor_name, self.fix, self.n_satellites), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_GPS_TM
+    msgname = "GPS_TM"
+    fieldnames = ["timestamp", "sensor_name", "fix", "latitude", "longitude", "height", "vel_north", "vel_east", "vel_down", "speed", "track", "n_satellites"]
+    ordered_fieldnames = ["timestamp", "latitude", "longitude", "height", "vel_north", "vel_east", "vel_down", "speed", "track", "sensor_name", "fix", "n_satellites"]
+    fieldtypes = ["uint64_t", "char", "uint8_t", "double", "double", "double", "float", "float", "float", "float", "float", "uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "latitude": "deg", "longitude": "deg", "height": "m", "vel_north": "m/s", "vel_east": "m/s", "vel_down": "m/s", "speed": "m/s", "track": "deg"}
+    native_format = bytearray(b"<QdddfffffcBB")
+    orders = [0, 9, 10, 1, 2, 3, 4, 5, 6, 7, 8, 11]
+    lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 0, 0]
+    crc_extra = 57
+    unpacker = struct.Struct("<Qdddfffff20sBB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, sensor_name: bytes, fix: int, latitude: float, longitude: float, height: float, vel_north: float, vel_east: float, vel_down: float, speed: float, track: float, n_satellites: int):
+        MAVLink_message.__init__(self, MAVLink_gps_tm_message.id, MAVLink_gps_tm_message.msgname)
+        self._fieldnames = MAVLink_gps_tm_message.fieldnames
+        self._instance_field = MAVLink_gps_tm_message.instance_field
+        self._instance_offset = MAVLink_gps_tm_message.instance_offset
+        self.timestamp = timestamp
+        self._sensor_name_raw = sensor_name
+        self.sensor_name = sensor_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.fix = fix
+        self.latitude = latitude
+        self.longitude = longitude
+        self.height = height
+        self.vel_north = vel_north
+        self.vel_east = vel_east
+        self.vel_down = vel_down
+        self.speed = speed
+        self.track = track
+        self.n_satellites = n_satellites
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.latitude, self.longitude, self.height, self.vel_north, self.vel_east, self.vel_down, self.speed, self.track, self._sensor_name_raw, self.fix, self.n_satellites), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_gps_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_imu_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_IMU_TM
-        name = 'IMU_TM'
-        fieldnames = ['timestamp', 'sensor_name', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z']
-        ordered_fieldnames = ['timestamp', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'sensor_name']
-        fieldtypes = ['uint64_t', 'char', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "acc_x": "m/s2", "acc_y": "m/s2", "acc_z": "m/s2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT"}
-        format = '<Qfffffffff20s'
-        native_format = bytearray('<Qfffffffffc', 'ascii')
-        orders = [0, 10, 1, 2, 3, 4, 5, 6, 7, 8, 9]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20]
-        crc_extra = 72
-        unpacker = struct.Struct('<Qfffffffff20s')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, sensor_name, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z):
-                MAVLink_message.__init__(self, MAVLink_imu_tm_message.id, MAVLink_imu_tm_message.name)
-                self._fieldnames = MAVLink_imu_tm_message.fieldnames
-                self._instance_field = MAVLink_imu_tm_message.instance_field
-                self._instance_offset = MAVLink_imu_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.sensor_name = sensor_name
-                self.acc_x = acc_x
-                self.acc_y = acc_y
-                self.acc_z = acc_z
-                self.gyro_x = gyro_x
-                self.gyro_y = gyro_y
-                self.gyro_z = gyro_z
-                self.mag_x = mag_x
-                self.mag_y = mag_y
-                self.mag_z = mag_z
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 72, struct.pack('<Qfffffffff20s', self.timestamp, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.sensor_name), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_IMU_TM
+    msgname = "IMU_TM"
+    fieldnames = ["timestamp", "sensor_name", "acc_x", "acc_y", "acc_z", "gyro_x", "gyro_y", "gyro_z", "mag_x", "mag_y", "mag_z"]
+    ordered_fieldnames = ["timestamp", "acc_x", "acc_y", "acc_z", "gyro_x", "gyro_y", "gyro_z", "mag_x", "mag_y", "mag_z", "sensor_name"]
+    fieldtypes = ["uint64_t", "char", "float", "float", "float", "float", "float", "float", "float", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "acc_x": "m/s2", "acc_y": "m/s2", "acc_z": "m/s2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT"}
+    native_format = bytearray(b"<Qfffffffffc")
+    orders = [0, 10, 1, 2, 3, 4, 5, 6, 7, 8, 9]
+    lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20]
+    crc_extra = 72
+    unpacker = struct.Struct("<Qfffffffff20s")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, sensor_name: bytes, acc_x: float, acc_y: float, acc_z: float, gyro_x: float, gyro_y: float, gyro_z: float, mag_x: float, mag_y: float, mag_z: float):
+        MAVLink_message.__init__(self, MAVLink_imu_tm_message.id, MAVLink_imu_tm_message.msgname)
+        self._fieldnames = MAVLink_imu_tm_message.fieldnames
+        self._instance_field = MAVLink_imu_tm_message.instance_field
+        self._instance_offset = MAVLink_imu_tm_message.instance_offset
+        self.timestamp = timestamp
+        self._sensor_name_raw = sensor_name
+        self.sensor_name = sensor_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.acc_x = acc_x
+        self.acc_y = acc_y
+        self.acc_z = acc_z
+        self.gyro_x = gyro_x
+        self.gyro_y = gyro_y
+        self.gyro_z = gyro_z
+        self.mag_x = mag_x
+        self.mag_y = mag_y
+        self.mag_z = mag_z
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self._sensor_name_raw), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_imu_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_pressure_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_PRESSURE_TM
-        name = 'PRESSURE_TM'
-        fieldnames = ['timestamp', 'sensor_name', 'pressure']
-        ordered_fieldnames = ['timestamp', 'pressure', 'sensor_name']
-        fieldtypes = ['uint64_t', 'char', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "pressure": "Pa"}
-        format = '<Qf20s'
-        native_format = bytearray('<Qfc', 'ascii')
-        orders = [0, 2, 1]
-        lengths = [1, 1, 1]
-        array_lengths = [0, 0, 20]
-        crc_extra = 87
-        unpacker = struct.Struct('<Qf20s')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, sensor_name, pressure):
-                MAVLink_message.__init__(self, MAVLink_pressure_tm_message.id, MAVLink_pressure_tm_message.name)
-                self._fieldnames = MAVLink_pressure_tm_message.fieldnames
-                self._instance_field = MAVLink_pressure_tm_message.instance_field
-                self._instance_offset = MAVLink_pressure_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.sensor_name = sensor_name
-                self.pressure = pressure
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 87, struct.pack('<Qf20s', self.timestamp, self.pressure, self.sensor_name), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_PRESSURE_TM
+    msgname = "PRESSURE_TM"
+    fieldnames = ["timestamp", "sensor_name", "pressure"]
+    ordered_fieldnames = ["timestamp", "pressure", "sensor_name"]
+    fieldtypes = ["uint64_t", "char", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "pressure": "Pa"}
+    native_format = bytearray(b"<Qfc")
+    orders = [0, 2, 1]
+    lengths = [1, 1, 1]
+    array_lengths = [0, 0, 20]
+    crc_extra = 87
+    unpacker = struct.Struct("<Qf20s")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, sensor_name: bytes, pressure: float):
+        MAVLink_message.__init__(self, MAVLink_pressure_tm_message.id, MAVLink_pressure_tm_message.msgname)
+        self._fieldnames = MAVLink_pressure_tm_message.fieldnames
+        self._instance_field = MAVLink_pressure_tm_message.instance_field
+        self._instance_offset = MAVLink_pressure_tm_message.instance_offset
+        self.timestamp = timestamp
+        self._sensor_name_raw = sensor_name
+        self.sensor_name = sensor_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.pressure = pressure
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.pressure, self._sensor_name_raw), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_pressure_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_adc_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_ADC_TM
-        name = 'ADC_TM'
-        fieldnames = ['timestamp', 'sensor_name', 'channel_0', 'channel_1', 'channel_2', 'channel_3', 'channel_4', 'channel_5', 'channel_6', 'channel_7']
-        ordered_fieldnames = ['timestamp', 'channel_0', 'channel_1', 'channel_2', 'channel_3', 'channel_4', 'channel_5', 'channel_6', 'channel_7', 'sensor_name']
-        fieldtypes = ['uint64_t', 'char', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "channel_0": "V", "channel_1": "V", "channel_2": "V", "channel_3": "V", "channel_4": "V", "channel_5": "V", "channel_6": "V", "channel_7": "V"}
-        format = '<Qffffffff20s'
-        native_format = bytearray('<Qffffffffc', 'ascii')
-        orders = [0, 9, 1, 2, 3, 4, 5, 6, 7, 8]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 20]
-        crc_extra = 229
-        unpacker = struct.Struct('<Qffffffff20s')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7):
-                MAVLink_message.__init__(self, MAVLink_adc_tm_message.id, MAVLink_adc_tm_message.name)
-                self._fieldnames = MAVLink_adc_tm_message.fieldnames
-                self._instance_field = MAVLink_adc_tm_message.instance_field
-                self._instance_offset = MAVLink_adc_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.sensor_name = sensor_name
-                self.channel_0 = channel_0
-                self.channel_1 = channel_1
-                self.channel_2 = channel_2
-                self.channel_3 = channel_3
-                self.channel_4 = channel_4
-                self.channel_5 = channel_5
-                self.channel_6 = channel_6
-                self.channel_7 = channel_7
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 229, struct.pack('<Qffffffff20s', self.timestamp, self.channel_0, self.channel_1, self.channel_2, self.channel_3, self.channel_4, self.channel_5, self.channel_6, self.channel_7, self.sensor_name), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_ADC_TM
+    msgname = "ADC_TM"
+    fieldnames = ["timestamp", "sensor_name", "channel_0", "channel_1", "channel_2", "channel_3", "channel_4", "channel_5", "channel_6", "channel_7"]
+    ordered_fieldnames = ["timestamp", "channel_0", "channel_1", "channel_2", "channel_3", "channel_4", "channel_5", "channel_6", "channel_7", "sensor_name"]
+    fieldtypes = ["uint64_t", "char", "float", "float", "float", "float", "float", "float", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "channel_0": "V", "channel_1": "V", "channel_2": "V", "channel_3": "V", "channel_4": "V", "channel_5": "V", "channel_6": "V", "channel_7": "V"}
+    native_format = bytearray(b"<Qffffffffc")
+    orders = [0, 9, 1, 2, 3, 4, 5, 6, 7, 8]
+    lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 20]
+    crc_extra = 229
+    unpacker = struct.Struct("<Qffffffff20s")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, sensor_name: bytes, channel_0: float, channel_1: float, channel_2: float, channel_3: float, channel_4: float, channel_5: float, channel_6: float, channel_7: float):
+        MAVLink_message.__init__(self, MAVLink_adc_tm_message.id, MAVLink_adc_tm_message.msgname)
+        self._fieldnames = MAVLink_adc_tm_message.fieldnames
+        self._instance_field = MAVLink_adc_tm_message.instance_field
+        self._instance_offset = MAVLink_adc_tm_message.instance_offset
+        self.timestamp = timestamp
+        self._sensor_name_raw = sensor_name
+        self.sensor_name = sensor_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.channel_0 = channel_0
+        self.channel_1 = channel_1
+        self.channel_2 = channel_2
+        self.channel_3 = channel_3
+        self.channel_4 = channel_4
+        self.channel_5 = channel_5
+        self.channel_6 = channel_6
+        self.channel_7 = channel_7
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.channel_0, self.channel_1, self.channel_2, self.channel_3, self.channel_4, self.channel_5, self.channel_6, self.channel_7, self._sensor_name_raw), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_adc_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_voltage_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_VOLTAGE_TM
-        name = 'VOLTAGE_TM'
-        fieldnames = ['timestamp', 'sensor_name', 'voltage']
-        ordered_fieldnames = ['timestamp', 'voltage', 'sensor_name']
-        fieldtypes = ['uint64_t', 'char', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "voltage": "V"}
-        format = '<Qf20s'
-        native_format = bytearray('<Qfc', 'ascii')
-        orders = [0, 2, 1]
-        lengths = [1, 1, 1]
-        array_lengths = [0, 0, 20]
-        crc_extra = 245
-        unpacker = struct.Struct('<Qf20s')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, sensor_name, voltage):
-                MAVLink_message.__init__(self, MAVLink_voltage_tm_message.id, MAVLink_voltage_tm_message.name)
-                self._fieldnames = MAVLink_voltage_tm_message.fieldnames
-                self._instance_field = MAVLink_voltage_tm_message.instance_field
-                self._instance_offset = MAVLink_voltage_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.sensor_name = sensor_name
-                self.voltage = voltage
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 245, struct.pack('<Qf20s', self.timestamp, self.voltage, self.sensor_name), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_VOLTAGE_TM
+    msgname = "VOLTAGE_TM"
+    fieldnames = ["timestamp", "sensor_name", "voltage"]
+    ordered_fieldnames = ["timestamp", "voltage", "sensor_name"]
+    fieldtypes = ["uint64_t", "char", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "voltage": "V"}
+    native_format = bytearray(b"<Qfc")
+    orders = [0, 2, 1]
+    lengths = [1, 1, 1]
+    array_lengths = [0, 0, 20]
+    crc_extra = 245
+    unpacker = struct.Struct("<Qf20s")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, sensor_name: bytes, voltage: float):
+        MAVLink_message.__init__(self, MAVLink_voltage_tm_message.id, MAVLink_voltage_tm_message.msgname)
+        self._fieldnames = MAVLink_voltage_tm_message.fieldnames
+        self._instance_field = MAVLink_voltage_tm_message.instance_field
+        self._instance_offset = MAVLink_voltage_tm_message.instance_offset
+        self.timestamp = timestamp
+        self._sensor_name_raw = sensor_name
+        self.sensor_name = sensor_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.voltage = voltage
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.voltage, self._sensor_name_raw), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_voltage_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_current_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_CURRENT_TM
-        name = 'CURRENT_TM'
-        fieldnames = ['timestamp', 'sensor_name', 'current']
-        ordered_fieldnames = ['timestamp', 'current', 'sensor_name']
-        fieldtypes = ['uint64_t', 'char', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "current": "A"}
-        format = '<Qf20s'
-        native_format = bytearray('<Qfc', 'ascii')
-        orders = [0, 2, 1]
-        lengths = [1, 1, 1]
-        array_lengths = [0, 0, 20]
-        crc_extra = 212
-        unpacker = struct.Struct('<Qf20s')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, sensor_name, current):
-                MAVLink_message.__init__(self, MAVLink_current_tm_message.id, MAVLink_current_tm_message.name)
-                self._fieldnames = MAVLink_current_tm_message.fieldnames
-                self._instance_field = MAVLink_current_tm_message.instance_field
-                self._instance_offset = MAVLink_current_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.sensor_name = sensor_name
-                self.current = current
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 212, struct.pack('<Qf20s', self.timestamp, self.current, self.sensor_name), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_CURRENT_TM
+    msgname = "CURRENT_TM"
+    fieldnames = ["timestamp", "sensor_name", "current"]
+    ordered_fieldnames = ["timestamp", "current", "sensor_name"]
+    fieldtypes = ["uint64_t", "char", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "current": "A"}
+    native_format = bytearray(b"<Qfc")
+    orders = [0, 2, 1]
+    lengths = [1, 1, 1]
+    array_lengths = [0, 0, 20]
+    crc_extra = 212
+    unpacker = struct.Struct("<Qf20s")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, sensor_name: bytes, current: float):
+        MAVLink_message.__init__(self, MAVLink_current_tm_message.id, MAVLink_current_tm_message.msgname)
+        self._fieldnames = MAVLink_current_tm_message.fieldnames
+        self._instance_field = MAVLink_current_tm_message.instance_field
+        self._instance_offset = MAVLink_current_tm_message.instance_offset
+        self.timestamp = timestamp
+        self._sensor_name_raw = sensor_name
+        self.sensor_name = sensor_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.current = current
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.current, self._sensor_name_raw), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_current_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_temp_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_TEMP_TM
-        name = 'TEMP_TM'
-        fieldnames = ['timestamp', 'sensor_name', 'temperature']
-        ordered_fieldnames = ['timestamp', 'temperature', 'sensor_name']
-        fieldtypes = ['uint64_t', 'char', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "temperature": "deg"}
-        format = '<Qf20s'
-        native_format = bytearray('<Qfc', 'ascii')
-        orders = [0, 2, 1]
-        lengths = [1, 1, 1]
-        array_lengths = [0, 0, 20]
-        crc_extra = 140
-        unpacker = struct.Struct('<Qf20s')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, sensor_name, temperature):
-                MAVLink_message.__init__(self, MAVLink_temp_tm_message.id, MAVLink_temp_tm_message.name)
-                self._fieldnames = MAVLink_temp_tm_message.fieldnames
-                self._instance_field = MAVLink_temp_tm_message.instance_field
-                self._instance_offset = MAVLink_temp_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.sensor_name = sensor_name
-                self.temperature = temperature
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 140, struct.pack('<Qf20s', self.timestamp, self.temperature, self.sensor_name), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_TEMP_TM
+    msgname = "TEMP_TM"
+    fieldnames = ["timestamp", "sensor_name", "temperature"]
+    ordered_fieldnames = ["timestamp", "temperature", "sensor_name"]
+    fieldtypes = ["uint64_t", "char", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "temperature": "deg"}
+    native_format = bytearray(b"<Qfc")
+    orders = [0, 2, 1]
+    lengths = [1, 1, 1]
+    array_lengths = [0, 0, 20]
+    crc_extra = 140
+    unpacker = struct.Struct("<Qf20s")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, sensor_name: bytes, temperature: float):
+        MAVLink_message.__init__(self, MAVLink_temp_tm_message.id, MAVLink_temp_tm_message.msgname)
+        self._fieldnames = MAVLink_temp_tm_message.fieldnames
+        self._instance_field = MAVLink_temp_tm_message.instance_field
+        self._instance_offset = MAVLink_temp_tm_message.instance_offset
+        self.timestamp = timestamp
+        self._sensor_name_raw = sensor_name
+        self.sensor_name = sensor_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.temperature = temperature
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.temperature, self._sensor_name_raw), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_temp_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_load_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_LOAD_TM
-        name = 'LOAD_TM'
-        fieldnames = ['timestamp', 'sensor_name', 'load']
-        ordered_fieldnames = ['timestamp', 'load', 'sensor_name']
-        fieldtypes = ['uint64_t', 'char', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "load": "kg"}
-        format = '<Qf20s'
-        native_format = bytearray('<Qfc', 'ascii')
-        orders = [0, 2, 1]
-        lengths = [1, 1, 1]
-        array_lengths = [0, 0, 20]
-        crc_extra = 148
-        unpacker = struct.Struct('<Qf20s')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, sensor_name, load):
-                MAVLink_message.__init__(self, MAVLink_load_tm_message.id, MAVLink_load_tm_message.name)
-                self._fieldnames = MAVLink_load_tm_message.fieldnames
-                self._instance_field = MAVLink_load_tm_message.instance_field
-                self._instance_offset = MAVLink_load_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.sensor_name = sensor_name
-                self.load = load
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 148, struct.pack('<Qf20s', self.timestamp, self.load, self.sensor_name), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_LOAD_TM
+    msgname = "LOAD_TM"
+    fieldnames = ["timestamp", "sensor_name", "load"]
+    ordered_fieldnames = ["timestamp", "load", "sensor_name"]
+    fieldtypes = ["uint64_t", "char", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "load": "kg"}
+    native_format = bytearray(b"<Qfc")
+    orders = [0, 2, 1]
+    lengths = [1, 1, 1]
+    array_lengths = [0, 0, 20]
+    crc_extra = 148
+    unpacker = struct.Struct("<Qf20s")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, sensor_name: bytes, load: float):
+        MAVLink_message.__init__(self, MAVLink_load_tm_message.id, MAVLink_load_tm_message.msgname)
+        self._fieldnames = MAVLink_load_tm_message.fieldnames
+        self._instance_field = MAVLink_load_tm_message.instance_field
+        self._instance_offset = MAVLink_load_tm_message.instance_offset
+        self.timestamp = timestamp
+        self._sensor_name_raw = sensor_name
+        self.sensor_name = sensor_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.load = load
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.load, self._sensor_name_raw), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_load_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_attitude_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_ATTITUDE_TM
-        name = 'ATTITUDE_TM'
-        fieldnames = ['timestamp', 'sensor_name', 'roll', 'pitch', 'yaw', 'quat_x', 'quat_y', 'quat_z', 'quat_w']
-        ordered_fieldnames = ['timestamp', 'roll', 'pitch', 'yaw', 'quat_x', 'quat_y', 'quat_z', 'quat_w', 'sensor_name']
-        fieldtypes = ['uint64_t', 'char', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "roll": "deg", "pitch": "deg", "yaw": "deg"}
-        format = '<Qfffffff20s'
-        native_format = bytearray('<Qfffffffc', 'ascii')
-        orders = [0, 8, 1, 2, 3, 4, 5, 6, 7]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 20]
-        crc_extra = 6
-        unpacker = struct.Struct('<Qfffffff20s')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w):
-                MAVLink_message.__init__(self, MAVLink_attitude_tm_message.id, MAVLink_attitude_tm_message.name)
-                self._fieldnames = MAVLink_attitude_tm_message.fieldnames
-                self._instance_field = MAVLink_attitude_tm_message.instance_field
-                self._instance_offset = MAVLink_attitude_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.sensor_name = sensor_name
-                self.roll = roll
-                self.pitch = pitch
-                self.yaw = yaw
-                self.quat_x = quat_x
-                self.quat_y = quat_y
-                self.quat_z = quat_z
-                self.quat_w = quat_w
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 6, struct.pack('<Qfffffff20s', self.timestamp, self.roll, self.pitch, self.yaw, self.quat_x, self.quat_y, self.quat_z, self.quat_w, self.sensor_name), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_ATTITUDE_TM
+    msgname = "ATTITUDE_TM"
+    fieldnames = ["timestamp", "sensor_name", "roll", "pitch", "yaw", "quat_x", "quat_y", "quat_z", "quat_w"]
+    ordered_fieldnames = ["timestamp", "roll", "pitch", "yaw", "quat_x", "quat_y", "quat_z", "quat_w", "sensor_name"]
+    fieldtypes = ["uint64_t", "char", "float", "float", "float", "float", "float", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "roll": "deg", "pitch": "deg", "yaw": "deg"}
+    native_format = bytearray(b"<Qfffffffc")
+    orders = [0, 8, 1, 2, 3, 4, 5, 6, 7]
+    lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 20]
+    crc_extra = 6
+    unpacker = struct.Struct("<Qfffffff20s")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, sensor_name: bytes, roll: float, pitch: float, yaw: float, quat_x: float, quat_y: float, quat_z: float, quat_w: float):
+        MAVLink_message.__init__(self, MAVLink_attitude_tm_message.id, MAVLink_attitude_tm_message.msgname)
+        self._fieldnames = MAVLink_attitude_tm_message.fieldnames
+        self._instance_field = MAVLink_attitude_tm_message.instance_field
+        self._instance_offset = MAVLink_attitude_tm_message.instance_offset
+        self.timestamp = timestamp
+        self._sensor_name_raw = sensor_name
+        self.sensor_name = sensor_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.roll = roll
+        self.pitch = pitch
+        self.yaw = yaw
+        self.quat_x = quat_x
+        self.quat_y = quat_y
+        self.quat_z = quat_z
+        self.quat_w = quat_w
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.roll, self.pitch, self.yaw, self.quat_x, self.quat_y, self.quat_z, self.quat_w, self._sensor_name_raw), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_attitude_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_sensor_state_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_SENSOR_STATE_TM
-        name = 'SENSOR_STATE_TM'
-        fieldnames = ['sensor_name', 'initialized', 'enabled']
-        ordered_fieldnames = ['sensor_name', 'initialized', 'enabled']
-        fieldtypes = ['char', 'uint8_t', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<20sBB'
-        native_format = bytearray('<cBB', 'ascii')
-        orders = [0, 1, 2]
-        lengths = [1, 1, 1]
-        array_lengths = [20, 0, 0]
-        crc_extra = 165
-        unpacker = struct.Struct('<20sBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, sensor_name, initialized, enabled):
-                MAVLink_message.__init__(self, MAVLink_sensor_state_tm_message.id, MAVLink_sensor_state_tm_message.name)
-                self._fieldnames = MAVLink_sensor_state_tm_message.fieldnames
-                self._instance_field = MAVLink_sensor_state_tm_message.instance_field
-                self._instance_offset = MAVLink_sensor_state_tm_message.instance_offset
-                self.sensor_name = sensor_name
-                self.initialized = initialized
-                self.enabled = enabled
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 165, struct.pack('<20sBB', self.sensor_name, self.initialized, self.enabled), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_SENSOR_STATE_TM
+    msgname = "SENSOR_STATE_TM"
+    fieldnames = ["sensor_name", "initialized", "enabled"]
+    ordered_fieldnames = ["sensor_name", "initialized", "enabled"]
+    fieldtypes = ["char", "uint8_t", "uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<cBB")
+    orders = [0, 1, 2]
+    lengths = [1, 1, 1]
+    array_lengths = [20, 0, 0]
+    crc_extra = 165
+    unpacker = struct.Struct("<20sBB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, sensor_name: bytes, initialized: int, enabled: int):
+        MAVLink_message.__init__(self, MAVLink_sensor_state_tm_message.id, MAVLink_sensor_state_tm_message.msgname)
+        self._fieldnames = MAVLink_sensor_state_tm_message.fieldnames
+        self._instance_field = MAVLink_sensor_state_tm_message.instance_field
+        self._instance_offset = MAVLink_sensor_state_tm_message.instance_offset
+        self._sensor_name_raw = sensor_name
+        self.sensor_name = sensor_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.initialized = initialized
+        self.enabled = enabled
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self._sensor_name_raw, self.initialized, self.enabled), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_sensor_state_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_servo_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_SERVO_TM
-        name = 'SERVO_TM'
-        fieldnames = ['servo_id', 'servo_position']
-        ordered_fieldnames = ['servo_position', 'servo_id']
-        fieldtypes = ['uint8_t', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {}
-        format = '<fB'
-        native_format = bytearray('<fB', 'ascii')
-        orders = [1, 0]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 87
-        unpacker = struct.Struct('<fB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, servo_id, servo_position):
-                MAVLink_message.__init__(self, MAVLink_servo_tm_message.id, MAVLink_servo_tm_message.name)
-                self._fieldnames = MAVLink_servo_tm_message.fieldnames
-                self._instance_field = MAVLink_servo_tm_message.instance_field
-                self._instance_offset = MAVLink_servo_tm_message.instance_offset
-                self.servo_id = servo_id
-                self.servo_position = servo_position
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 87, struct.pack('<fB', self.servo_position, self.servo_id), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_SERVO_TM
+    msgname = "SERVO_TM"
+    fieldnames = ["servo_id", "servo_position"]
+    ordered_fieldnames = ["servo_position", "servo_id"]
+    fieldtypes = ["uint8_t", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<fB")
+    orders = [1, 0]
+    lengths = [1, 1]
+    array_lengths = [0, 0]
+    crc_extra = 87
+    unpacker = struct.Struct("<fB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, servo_id: int, servo_position: float):
+        MAVLink_message.__init__(self, MAVLink_servo_tm_message.id, MAVLink_servo_tm_message.msgname)
+        self._fieldnames = MAVLink_servo_tm_message.fieldnames
+        self._instance_field = MAVLink_servo_tm_message.instance_field
+        self._instance_offset = MAVLink_servo_tm_message.instance_offset
+        self.servo_id = servo_id
+        self.servo_position = servo_position
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.servo_position, self.servo_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_servo_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_pin_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_PIN_TM
-        name = 'PIN_TM'
-        fieldnames = ['timestamp', 'pin_id', 'last_change_timestamp', 'changes_counter', 'current_state']
-        ordered_fieldnames = ['timestamp', 'last_change_timestamp', 'pin_id', 'changes_counter', 'current_state']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint64_t', 'uint8_t', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us"}
-        format = '<QQBBB'
-        native_format = bytearray('<QQBBB', 'ascii')
-        orders = [0, 2, 1, 3, 4]
-        lengths = [1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0]
-        crc_extra = 255
-        unpacker = struct.Struct('<QQBBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, pin_id, last_change_timestamp, changes_counter, current_state):
-                MAVLink_message.__init__(self, MAVLink_pin_tm_message.id, MAVLink_pin_tm_message.name)
-                self._fieldnames = MAVLink_pin_tm_message.fieldnames
-                self._instance_field = MAVLink_pin_tm_message.instance_field
-                self._instance_offset = MAVLink_pin_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.pin_id = pin_id
-                self.last_change_timestamp = last_change_timestamp
-                self.changes_counter = changes_counter
-                self.current_state = current_state
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 255, struct.pack('<QQBBB', self.timestamp, self.last_change_timestamp, self.pin_id, self.changes_counter, self.current_state), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_PIN_TM
+    msgname = "PIN_TM"
+    fieldnames = ["timestamp", "pin_id", "last_change_timestamp", "changes_counter", "current_state"]
+    ordered_fieldnames = ["timestamp", "last_change_timestamp", "pin_id", "changes_counter", "current_state"]
+    fieldtypes = ["uint64_t", "uint8_t", "uint64_t", "uint8_t", "uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us"}
+    native_format = bytearray(b"<QQBBB")
+    orders = [0, 2, 1, 3, 4]
+    lengths = [1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0]
+    crc_extra = 255
+    unpacker = struct.Struct("<QQBBB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, pin_id: int, last_change_timestamp: int, changes_counter: int, current_state: int):
+        MAVLink_message.__init__(self, MAVLink_pin_tm_message.id, MAVLink_pin_tm_message.msgname)
+        self._fieldnames = MAVLink_pin_tm_message.fieldnames
+        self._instance_field = MAVLink_pin_tm_message.instance_field
+        self._instance_offset = MAVLink_pin_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.pin_id = pin_id
+        self.last_change_timestamp = last_change_timestamp
+        self.changes_counter = changes_counter
+        self.current_state = current_state
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.last_change_timestamp, self.pin_id, self.changes_counter, self.current_state), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_pin_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_registry_float_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_REGISTRY_FLOAT_TM
-        name = 'REGISTRY_FLOAT_TM'
-        fieldnames = ['timestamp', 'key_id', 'key_name', 'value']
-        ordered_fieldnames = ['timestamp', 'key_id', 'value', 'key_name']
-        fieldtypes = ['uint64_t', 'uint32_t', 'char', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us"}
-        format = '<QIf20s'
-        native_format = bytearray('<QIfc', 'ascii')
-        orders = [0, 1, 3, 2]
-        lengths = [1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 20]
-        crc_extra = 9
-        unpacker = struct.Struct('<QIf20s')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, key_id, key_name, value):
-                MAVLink_message.__init__(self, MAVLink_registry_float_tm_message.id, MAVLink_registry_float_tm_message.name)
-                self._fieldnames = MAVLink_registry_float_tm_message.fieldnames
-                self._instance_field = MAVLink_registry_float_tm_message.instance_field
-                self._instance_offset = MAVLink_registry_float_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.key_id = key_id
-                self.key_name = key_name
-                self.value = value
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 9, struct.pack('<QIf20s', self.timestamp, self.key_id, self.value, self.key_name), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_REGISTRY_FLOAT_TM
+    msgname = "REGISTRY_FLOAT_TM"
+    fieldnames = ["timestamp", "key_id", "key_name", "value"]
+    ordered_fieldnames = ["timestamp", "key_id", "value", "key_name"]
+    fieldtypes = ["uint64_t", "uint32_t", "char", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us"}
+    native_format = bytearray(b"<QIfc")
+    orders = [0, 1, 3, 2]
+    lengths = [1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 20]
+    crc_extra = 9
+    unpacker = struct.Struct("<QIf20s")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, key_id: int, key_name: bytes, value: float):
+        MAVLink_message.__init__(self, MAVLink_registry_float_tm_message.id, MAVLink_registry_float_tm_message.msgname)
+        self._fieldnames = MAVLink_registry_float_tm_message.fieldnames
+        self._instance_field = MAVLink_registry_float_tm_message.instance_field
+        self._instance_offset = MAVLink_registry_float_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.key_id = key_id
+        self._key_name_raw = key_name
+        self.key_name = key_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.value = value
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.key_id, self.value, self._key_name_raw), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_registry_float_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_registry_int_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_REGISTRY_INT_TM
-        name = 'REGISTRY_INT_TM'
-        fieldnames = ['timestamp', 'key_id', 'key_name', 'value']
-        ordered_fieldnames = ['timestamp', 'key_id', 'value', 'key_name']
-        fieldtypes = ['uint64_t', 'uint32_t', 'char', 'uint32_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us"}
-        format = '<QII20s'
-        native_format = bytearray('<QIIc', 'ascii')
-        orders = [0, 1, 3, 2]
-        lengths = [1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 20]
-        crc_extra = 68
-        unpacker = struct.Struct('<QII20s')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, key_id, key_name, value):
-                MAVLink_message.__init__(self, MAVLink_registry_int_tm_message.id, MAVLink_registry_int_tm_message.name)
-                self._fieldnames = MAVLink_registry_int_tm_message.fieldnames
-                self._instance_field = MAVLink_registry_int_tm_message.instance_field
-                self._instance_offset = MAVLink_registry_int_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.key_id = key_id
-                self.key_name = key_name
-                self.value = value
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 68, struct.pack('<QII20s', self.timestamp, self.key_id, self.value, self.key_name), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_REGISTRY_INT_TM
+    msgname = "REGISTRY_INT_TM"
+    fieldnames = ["timestamp", "key_id", "key_name", "value"]
+    ordered_fieldnames = ["timestamp", "key_id", "value", "key_name"]
+    fieldtypes = ["uint64_t", "uint32_t", "char", "uint32_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us"}
+    native_format = bytearray(b"<QIIc")
+    orders = [0, 1, 3, 2]
+    lengths = [1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 20]
+    crc_extra = 68
+    unpacker = struct.Struct("<QII20s")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, key_id: int, key_name: bytes, value: int):
+        MAVLink_message.__init__(self, MAVLink_registry_int_tm_message.id, MAVLink_registry_int_tm_message.msgname)
+        self._fieldnames = MAVLink_registry_int_tm_message.fieldnames
+        self._instance_field = MAVLink_registry_int_tm_message.instance_field
+        self._instance_offset = MAVLink_registry_int_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.key_id = key_id
+        self._key_name_raw = key_name
+        self.key_name = key_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.value = value
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.key_id, self.value, self._key_name_raw), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_registry_int_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_registry_coord_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_REGISTRY_COORD_TM
-        name = 'REGISTRY_COORD_TM'
-        fieldnames = ['timestamp', 'key_id', 'key_name', 'latitude', 'longitude']
-        ordered_fieldnames = ['timestamp', 'key_id', 'latitude', 'longitude', 'key_name']
-        fieldtypes = ['uint64_t', 'uint32_t', 'char', 'float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "latitude": "deg", "longitude": "deg"}
-        format = '<QIff20s'
-        native_format = bytearray('<QIffc', 'ascii')
-        orders = [0, 1, 4, 2, 3]
-        lengths = [1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 20]
-        crc_extra = 234
-        unpacker = struct.Struct('<QIff20s')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, key_id, key_name, latitude, longitude):
-                MAVLink_message.__init__(self, MAVLink_registry_coord_tm_message.id, MAVLink_registry_coord_tm_message.name)
-                self._fieldnames = MAVLink_registry_coord_tm_message.fieldnames
-                self._instance_field = MAVLink_registry_coord_tm_message.instance_field
-                self._instance_offset = MAVLink_registry_coord_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.key_id = key_id
-                self.key_name = key_name
-                self.latitude = latitude
-                self.longitude = longitude
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 234, struct.pack('<QIff20s', self.timestamp, self.key_id, self.latitude, self.longitude, self.key_name), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_REGISTRY_COORD_TM
+    msgname = "REGISTRY_COORD_TM"
+    fieldnames = ["timestamp", "key_id", "key_name", "latitude", "longitude"]
+    ordered_fieldnames = ["timestamp", "key_id", "latitude", "longitude", "key_name"]
+    fieldtypes = ["uint64_t", "uint32_t", "char", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "latitude": "deg", "longitude": "deg"}
+    native_format = bytearray(b"<QIffc")
+    orders = [0, 1, 4, 2, 3]
+    lengths = [1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 20]
+    crc_extra = 234
+    unpacker = struct.Struct("<QIff20s")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, key_id: int, key_name: bytes, latitude: float, longitude: float):
+        MAVLink_message.__init__(self, MAVLink_registry_coord_tm_message.id, MAVLink_registry_coord_tm_message.msgname)
+        self._fieldnames = MAVLink_registry_coord_tm_message.fieldnames
+        self._instance_field = MAVLink_registry_coord_tm_message.instance_field
+        self._instance_offset = MAVLink_registry_coord_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.key_id = key_id
+        self._key_name_raw = key_name
+        self.key_name = key_name.split(b"\x00", 1)[0].decode("ascii", errors="replace")
+        self.latitude = latitude
+        self.longitude = longitude
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.key_id, self.latitude, self.longitude, self._key_name_raw), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_registry_coord_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_arp_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_ARP_TM
-        name = 'ARP_TM'
-        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', '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']
-        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', 'gps_fix', 'main_radio_present', 'payload_radio_present', 'ethernet_present', 'ethernet_status']
-        fieldtypes = ['uint64_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']
-        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 = '<QfffffffffffffffffHHHHHHHHHHBBBBB'
-        native_format = bytearray('<QfffffffffffffffffHHHHHHHHHHBBBBB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 28, 29, 18, 19, 20, 21, 22, 15, 30, 23, 24, 25, 26, 27, 16, 31, 32, 17]
-        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]
-        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]
-        crc_extra = 22
-        unpacker = struct.Struct('<QfffffffffffffffffHHHHHHHHHHBBBBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, 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, 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):
-                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
-                self._instance_offset = MAVLink_arp_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.yaw = yaw
-                self.pitch = pitch
-                self.roll = roll
-                self.target_yaw = target_yaw
-                self.target_pitch = target_pitch
-                self.stepperX_pos = stepperX_pos
-                self.stepperX_delta = stepperX_delta
-                self.stepperX_speed = stepperX_speed
-                self.stepperY_pos = stepperY_pos
-                self.stepperY_delta = stepperY_delta
-                self.stepperY_speed = stepperY_speed
-                self.gps_latitude = gps_latitude
-                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
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 22, struct.pack('<QfffffffffffffffffHHHHHHHHHHBBBBB', 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.gps_fix, self.main_radio_present, self.payload_radio_present, self.ethernet_present, self.ethernet_status), force_mavlink1=force_mavlink1)
+    """
+
+    """
+
+    id = MAVLINK_MSG_ID_ARP_TM
+    msgname = "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"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"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"}
+    native_format = bytearray(b"<QfffffffffffffffffHHHHHHHHHHhBBBBBB")
+    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")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, state: int, 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: float, gps_fix: int, main_radio_present: int, main_packet_tx_error_count: int, main_tx_bitrate: int, main_packet_rx_success_count: int, main_packet_rx_drop_count: int, main_rx_bitrate: int, main_rx_rssi: float, payload_radio_present: int, payload_packet_tx_error_count: int, payload_tx_bitrate: int, payload_packet_rx_success_count: int, payload_packet_rx_drop_count: int, payload_rx_bitrate: int, payload_rx_rssi: float, ethernet_present: int, ethernet_status: int, battery_voltage: float, log_number: int):
+        MAVLink_message.__init__(self, MAVLink_arp_tm_message.id, MAVLink_arp_tm_message.msgname)
+        self._fieldnames = MAVLink_arp_tm_message.fieldnames
+        self._instance_field = MAVLink_arp_tm_message.instance_field
+        self._instance_offset = MAVLink_arp_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.state = state
+        self.yaw = yaw
+        self.pitch = pitch
+        self.roll = roll
+        self.target_yaw = target_yaw
+        self.target_pitch = target_pitch
+        self.stepperX_pos = stepperX_pos
+        self.stepperX_delta = stepperX_delta
+        self.stepperX_speed = stepperX_speed
+        self.stepperY_pos = stepperY_pos
+        self.stepperY_delta = stepperY_delta
+        self.stepperY_speed = stepperY_speed
+        self.gps_latitude = gps_latitude
+        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: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(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)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_arp_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_antenna_coordinates_arp_tc_message(MAVLink_message):
-        '''
-        Sets current antennas coordinates
-        '''
-        id = MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC
-        name = 'SET_ANTENNA_COORDINATES_ARP_TC'
-        fieldnames = ['latitude', 'longitude']
-        ordered_fieldnames = ['latitude', 'longitude']
-        fieldtypes = ['float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"latitude": "deg", "longitude": "deg"}
-        format = '<ff'
-        native_format = bytearray('<ff', 'ascii')
-        orders = [0, 1]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 202
-        unpacker = struct.Struct('<ff')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, latitude, longitude):
-                MAVLink_message.__init__(self, MAVLink_set_antenna_coordinates_arp_tc_message.id, MAVLink_set_antenna_coordinates_arp_tc_message.name)
-                self._fieldnames = MAVLink_set_antenna_coordinates_arp_tc_message.fieldnames
-                self._instance_field = MAVLink_set_antenna_coordinates_arp_tc_message.instance_field
-                self._instance_offset = MAVLink_set_antenna_coordinates_arp_tc_message.instance_offset
-                self.latitude = latitude
-                self.longitude = longitude
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 202, struct.pack('<ff', self.latitude, self.longitude), force_mavlink1=force_mavlink1)
+    """
+    Sets current antennas coordinates
+    """
+
+    id = MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC
+    msgname = "SET_ANTENNA_COORDINATES_ARP_TC"
+    fieldnames = ["latitude", "longitude", "height"]
+    ordered_fieldnames = ["latitude", "longitude", "height"]
+    fieldtypes = ["float", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"latitude": "deg", "longitude": "deg", "height": "m"}
+    native_format = bytearray(b"<fff")
+    orders = [0, 1, 2]
+    lengths = [1, 1, 1]
+    array_lengths = [0, 0, 0]
+    crc_extra = 183
+    unpacker = struct.Struct("<fff")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, latitude: float, longitude: float, height: float):
+        MAVLink_message.__init__(self, MAVLink_set_antenna_coordinates_arp_tc_message.id, MAVLink_set_antenna_coordinates_arp_tc_message.msgname)
+        self._fieldnames = MAVLink_set_antenna_coordinates_arp_tc_message.fieldnames
+        self._instance_field = MAVLink_set_antenna_coordinates_arp_tc_message.instance_field
+        self._instance_offset = MAVLink_set_antenna_coordinates_arp_tc_message.instance_offset
+        self.latitude = latitude
+        self.longitude = longitude
+        self.height = height
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.latitude, self.longitude, self.height), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_antenna_coordinates_arp_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_set_rocket_coordinates_arp_tc_message(MAVLink_message):
-        '''
-        Sets current rocket coordinates
-        '''
-        id = MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC
-        name = 'SET_ROCKET_COORDINATES_ARP_TC'
-        fieldnames = ['latitude', 'longitude']
-        ordered_fieldnames = ['latitude', 'longitude']
-        fieldtypes = ['float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"latitude": "deg", "longitude": "deg"}
-        format = '<ff'
-        native_format = bytearray('<ff', 'ascii')
-        orders = [0, 1]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 164
-        unpacker = struct.Struct('<ff')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, latitude, longitude):
-                MAVLink_message.__init__(self, MAVLink_set_rocket_coordinates_arp_tc_message.id, MAVLink_set_rocket_coordinates_arp_tc_message.name)
-                self._fieldnames = MAVLink_set_rocket_coordinates_arp_tc_message.fieldnames
-                self._instance_field = MAVLink_set_rocket_coordinates_arp_tc_message.instance_field
-                self._instance_offset = MAVLink_set_rocket_coordinates_arp_tc_message.instance_offset
-                self.latitude = latitude
-                self.longitude = longitude
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 164, struct.pack('<ff', self.latitude, self.longitude), force_mavlink1=force_mavlink1)
+    """
+    Sets current rocket coordinates
+    """
+
+    id = MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC
+    msgname = "SET_ROCKET_COORDINATES_ARP_TC"
+    fieldnames = ["latitude", "longitude", "height"]
+    ordered_fieldnames = ["latitude", "longitude", "height"]
+    fieldtypes = ["float", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"latitude": "deg", "longitude": "deg", "height": "m"}
+    native_format = bytearray(b"<fff")
+    orders = [0, 1, 2]
+    lengths = [1, 1, 1]
+    array_lengths = [0, 0, 0]
+    crc_extra = 220
+    unpacker = struct.Struct("<fff")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, latitude: float, longitude: float, height: float):
+        MAVLink_message.__init__(self, MAVLink_set_rocket_coordinates_arp_tc_message.id, MAVLink_set_rocket_coordinates_arp_tc_message.msgname)
+        self._fieldnames = MAVLink_set_rocket_coordinates_arp_tc_message.fieldnames
+        self._instance_field = MAVLink_set_rocket_coordinates_arp_tc_message.instance_field
+        self._instance_offset = MAVLink_set_rocket_coordinates_arp_tc_message.instance_offset
+        self.latitude = latitude
+        self.longitude = longitude
+        self.height = height
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.latitude, self.longitude, self.height), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_set_rocket_coordinates_arp_tc_message, "name", mavlink_msg_deprecated_name_property())
+
+
+class MAVLink_arp_command_tc_message(MAVLink_message):
+    """
+    TC containing a command with no parameters that trigger some
+    action
+    """
+
+    id = MAVLINK_MSG_ID_ARP_COMMAND_TC
+    msgname = "ARP_COMMAND_TC"
+    fieldnames = ["command_id"]
+    ordered_fieldnames = ["command_id"]
+    fieldtypes = ["uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {}
+    native_format = bytearray(b"<B")
+    orders = [0]
+    lengths = [1]
+    array_lengths = [0]
+    crc_extra = 181
+    unpacker = struct.Struct("<B")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, command_id: int):
+        MAVLink_message.__init__(self, MAVLink_arp_command_tc_message.id, MAVLink_arp_command_tc_message.msgname)
+        self._fieldnames = MAVLink_arp_command_tc_message.fieldnames
+        self._instance_field = MAVLink_arp_command_tc_message.instance_field
+        self._instance_offset = MAVLink_arp_command_tc_message.instance_offset
+        self.command_id = command_id
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.command_id), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_arp_command_tc_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_sys_tm_message(MAVLink_message):
-        '''
-        System status telemetry
-        '''
-        id = MAVLINK_MSG_ID_SYS_TM
-        name = 'SYS_TM'
-        fieldnames = ['timestamp', 'logger', 'event_broker', 'radio', 'sensors', 'actuators', 'pin_handler', 'can_handler', 'scheduler']
-        ordered_fieldnames = ['timestamp', 'logger', 'event_broker', 'radio', 'sensors', 'actuators', 'pin_handler', 'can_handler', 'scheduler']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us"}
-        format = '<QBBBBBBBB'
-        native_format = bytearray('<QBBBBBBBB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 48
-        unpacker = struct.Struct('<QBBBBBBBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler):
-                MAVLink_message.__init__(self, MAVLink_sys_tm_message.id, MAVLink_sys_tm_message.name)
-                self._fieldnames = MAVLink_sys_tm_message.fieldnames
-                self._instance_field = MAVLink_sys_tm_message.instance_field
-                self._instance_offset = MAVLink_sys_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.logger = logger
-                self.event_broker = event_broker
-                self.radio = radio
-                self.sensors = sensors
-                self.actuators = actuators
-                self.pin_handler = pin_handler
-                self.can_handler = can_handler
-                self.scheduler = scheduler
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 48, struct.pack('<QBBBBBBBB', self.timestamp, self.logger, self.event_broker, self.radio, self.sensors, self.actuators, self.pin_handler, self.can_handler, self.scheduler), force_mavlink1=force_mavlink1)
+    """
+    System status telemetry
+    """
+
+    id = MAVLINK_MSG_ID_SYS_TM
+    msgname = "SYS_TM"
+    fieldnames = ["timestamp", "logger", "event_broker", "radio", "sensors", "actuators", "pin_handler", "can_handler", "scheduler"]
+    ordered_fieldnames = ["timestamp", "logger", "event_broker", "radio", "sensors", "actuators", "pin_handler", "can_handler", "scheduler"]
+    fieldtypes = ["uint64_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us"}
+    native_format = bytearray(b"<QBBBBBBBB")
+    orders = [0, 1, 2, 3, 4, 5, 6, 7, 8]
+    lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0]
+    crc_extra = 48
+    unpacker = struct.Struct("<QBBBBBBBB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, logger: int, event_broker: int, radio: int, sensors: int, actuators: int, pin_handler: int, can_handler: int, scheduler: int):
+        MAVLink_message.__init__(self, MAVLink_sys_tm_message.id, MAVLink_sys_tm_message.msgname)
+        self._fieldnames = MAVLink_sys_tm_message.fieldnames
+        self._instance_field = MAVLink_sys_tm_message.instance_field
+        self._instance_offset = MAVLink_sys_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.logger = logger
+        self.event_broker = event_broker
+        self.radio = radio
+        self.sensors = sensors
+        self.actuators = actuators
+        self.pin_handler = pin_handler
+        self.can_handler = can_handler
+        self.scheduler = scheduler
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.logger, self.event_broker, self.radio, self.sensors, self.actuators, self.pin_handler, self.can_handler, self.scheduler), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_sys_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_logger_tm_message(MAVLink_message):
-        '''
-        Logger status telemetry
-        '''
-        id = MAVLINK_MSG_ID_LOGGER_TM
-        name = 'LOGGER_TM'
-        fieldnames = ['timestamp', 'log_number', 'too_large_samples', 'dropped_samples', 'queued_samples', 'buffers_filled', 'buffers_written', 'writes_failed', 'last_write_error', 'average_write_time', 'max_write_time']
-        ordered_fieldnames = ['timestamp', 'too_large_samples', 'dropped_samples', 'queued_samples', 'buffers_filled', 'buffers_written', 'writes_failed', 'last_write_error', 'average_write_time', 'max_write_time', 'log_number']
-        fieldtypes = ['uint64_t', 'int16_t', 'int32_t', 'int32_t', 'int32_t', 'int32_t', 'int32_t', 'int32_t', 'int32_t', 'int32_t', 'int32_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us"}
-        format = '<Qiiiiiiiiih'
-        native_format = bytearray('<Qiiiiiiiiih', 'ascii')
-        orders = [0, 10, 1, 2, 3, 4, 5, 6, 7, 8, 9]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 142
-        unpacker = struct.Struct('<Qiiiiiiiiih')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time):
-                MAVLink_message.__init__(self, MAVLink_logger_tm_message.id, MAVLink_logger_tm_message.name)
-                self._fieldnames = MAVLink_logger_tm_message.fieldnames
-                self._instance_field = MAVLink_logger_tm_message.instance_field
-                self._instance_offset = MAVLink_logger_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.log_number = log_number
-                self.too_large_samples = too_large_samples
-                self.dropped_samples = dropped_samples
-                self.queued_samples = queued_samples
-                self.buffers_filled = buffers_filled
-                self.buffers_written = buffers_written
-                self.writes_failed = writes_failed
-                self.last_write_error = last_write_error
-                self.average_write_time = average_write_time
-                self.max_write_time = max_write_time
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 142, struct.pack('<Qiiiiiiiiih', self.timestamp, self.too_large_samples, self.dropped_samples, self.queued_samples, self.buffers_filled, self.buffers_written, self.writes_failed, self.last_write_error, self.average_write_time, self.max_write_time, self.log_number), force_mavlink1=force_mavlink1)
+    """
+    Logger status telemetry
+    """
+
+    id = MAVLINK_MSG_ID_LOGGER_TM
+    msgname = "LOGGER_TM"
+    fieldnames = ["timestamp", "log_number", "too_large_samples", "dropped_samples", "queued_samples", "buffers_filled", "buffers_written", "writes_failed", "last_write_error", "average_write_time", "max_write_time"]
+    ordered_fieldnames = ["timestamp", "too_large_samples", "dropped_samples", "queued_samples", "buffers_filled", "buffers_written", "writes_failed", "last_write_error", "average_write_time", "max_write_time", "log_number"]
+    fieldtypes = ["uint64_t", "int16_t", "int32_t", "int32_t", "int32_t", "int32_t", "int32_t", "int32_t", "int32_t", "int32_t", "int32_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us"}
+    native_format = bytearray(b"<Qiiiiiiiiih")
+    orders = [0, 10, 1, 2, 3, 4, 5, 6, 7, 8, 9]
+    lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+    crc_extra = 142
+    unpacker = struct.Struct("<Qiiiiiiiiih")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, log_number: int, too_large_samples: int, dropped_samples: int, queued_samples: int, buffers_filled: int, buffers_written: int, writes_failed: int, last_write_error: int, average_write_time: int, max_write_time: int):
+        MAVLink_message.__init__(self, MAVLink_logger_tm_message.id, MAVLink_logger_tm_message.msgname)
+        self._fieldnames = MAVLink_logger_tm_message.fieldnames
+        self._instance_field = MAVLink_logger_tm_message.instance_field
+        self._instance_offset = MAVLink_logger_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.log_number = log_number
+        self.too_large_samples = too_large_samples
+        self.dropped_samples = dropped_samples
+        self.queued_samples = queued_samples
+        self.buffers_filled = buffers_filled
+        self.buffers_written = buffers_written
+        self.writes_failed = writes_failed
+        self.last_write_error = last_write_error
+        self.average_write_time = average_write_time
+        self.max_write_time = max_write_time
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.too_large_samples, self.dropped_samples, self.queued_samples, self.buffers_filled, self.buffers_written, self.writes_failed, self.last_write_error, self.average_write_time, self.max_write_time, self.log_number), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_logger_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_mavlink_stats_tm_message(MAVLink_message):
-        '''
-        Status of MavlinkDriver
-        '''
-        id = MAVLINK_MSG_ID_MAVLINK_STATS_TM
-        name = 'MAVLINK_STATS_TM'
-        fieldnames = ['timestamp', 'n_send_queue', 'max_send_queue', 'n_send_errors', 'msg_received', 'buffer_overrun', 'parse_error', 'parse_state', 'packet_idx', 'current_rx_seq', 'current_tx_seq', 'packet_rx_success_count', 'packet_rx_drop_count']
-        ordered_fieldnames = ['timestamp', 'parse_state', 'n_send_queue', 'max_send_queue', 'n_send_errors', 'packet_rx_success_count', 'packet_rx_drop_count', 'msg_received', 'buffer_overrun', 'parse_error', 'packet_idx', 'current_rx_seq', 'current_tx_seq']
-        fieldtypes = ['uint64_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint32_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint16_t', 'uint16_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us"}
-        format = '<QIHHHHHBBBBBB'
-        native_format = bytearray('<QIHHHHHBBBBBB', 'ascii')
-        orders = [0, 2, 3, 4, 7, 8, 9, 1, 10, 11, 12, 5, 6]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 108
-        unpacker = struct.Struct('<QIHHHHHBBBBBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count):
-                MAVLink_message.__init__(self, MAVLink_mavlink_stats_tm_message.id, MAVLink_mavlink_stats_tm_message.name)
-                self._fieldnames = MAVLink_mavlink_stats_tm_message.fieldnames
-                self._instance_field = MAVLink_mavlink_stats_tm_message.instance_field
-                self._instance_offset = MAVLink_mavlink_stats_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.n_send_queue = n_send_queue
-                self.max_send_queue = max_send_queue
-                self.n_send_errors = n_send_errors
-                self.msg_received = msg_received
-                self.buffer_overrun = buffer_overrun
-                self.parse_error = parse_error
-                self.parse_state = parse_state
-                self.packet_idx = packet_idx
-                self.current_rx_seq = current_rx_seq
-                self.current_tx_seq = current_tx_seq
-                self.packet_rx_success_count = packet_rx_success_count
-                self.packet_rx_drop_count = packet_rx_drop_count
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 108, struct.pack('<QIHHHHHBBBBBB', self.timestamp, self.parse_state, self.n_send_queue, self.max_send_queue, self.n_send_errors, self.packet_rx_success_count, self.packet_rx_drop_count, self.msg_received, self.buffer_overrun, self.parse_error, self.packet_idx, self.current_rx_seq, self.current_tx_seq), force_mavlink1=force_mavlink1)
+    """
+    Status of MavlinkDriver
+    """
+
+    id = MAVLINK_MSG_ID_MAVLINK_STATS_TM
+    msgname = "MAVLINK_STATS_TM"
+    fieldnames = ["timestamp", "n_send_queue", "max_send_queue", "n_send_errors", "msg_received", "buffer_overrun", "parse_error", "parse_state", "packet_idx", "current_rx_seq", "current_tx_seq", "packet_rx_success_count", "packet_rx_drop_count"]
+    ordered_fieldnames = ["timestamp", "parse_state", "n_send_queue", "max_send_queue", "n_send_errors", "packet_rx_success_count", "packet_rx_drop_count", "msg_received", "buffer_overrun", "parse_error", "packet_idx", "current_rx_seq", "current_tx_seq"]
+    fieldtypes = ["uint64_t", "uint16_t", "uint16_t", "uint16_t", "uint8_t", "uint8_t", "uint8_t", "uint32_t", "uint8_t", "uint8_t", "uint8_t", "uint16_t", "uint16_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us"}
+    native_format = bytearray(b"<QIHHHHHBBBBBB")
+    orders = [0, 2, 3, 4, 7, 8, 9, 1, 10, 11, 12, 5, 6]
+    lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+    crc_extra = 108
+    unpacker = struct.Struct("<QIHHHHHBBBBBB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, n_send_queue: int, max_send_queue: int, n_send_errors: int, msg_received: int, buffer_overrun: int, parse_error: int, parse_state: int, packet_idx: int, current_rx_seq: int, current_tx_seq: int, packet_rx_success_count: int, packet_rx_drop_count: int):
+        MAVLink_message.__init__(self, MAVLink_mavlink_stats_tm_message.id, MAVLink_mavlink_stats_tm_message.msgname)
+        self._fieldnames = MAVLink_mavlink_stats_tm_message.fieldnames
+        self._instance_field = MAVLink_mavlink_stats_tm_message.instance_field
+        self._instance_offset = MAVLink_mavlink_stats_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.n_send_queue = n_send_queue
+        self.max_send_queue = max_send_queue
+        self.n_send_errors = n_send_errors
+        self.msg_received = msg_received
+        self.buffer_overrun = buffer_overrun
+        self.parse_error = parse_error
+        self.parse_state = parse_state
+        self.packet_idx = packet_idx
+        self.current_rx_seq = current_rx_seq
+        self.current_tx_seq = current_tx_seq
+        self.packet_rx_success_count = packet_rx_success_count
+        self.packet_rx_drop_count = packet_rx_drop_count
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.parse_state, self.n_send_queue, self.max_send_queue, self.n_send_errors, self.packet_rx_success_count, self.packet_rx_drop_count, self.msg_received, self.buffer_overrun, self.parse_error, self.packet_idx, self.current_rx_seq, self.current_tx_seq), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_mavlink_stats_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_can_stats_tm_message(MAVLink_message):
-        '''
-        Status of CanHandler
-        '''
-        id = MAVLINK_MSG_ID_CAN_STATS_TM
-        name = 'CAN_STATS_TM'
-        fieldnames = ['timestamp', 'payload_bit_rate', 'total_bit_rate', 'load_percent']
-        ordered_fieldnames = ['timestamp', 'payload_bit_rate', 'total_bit_rate', 'load_percent']
-        fieldtypes = ['uint64_t', 'float', 'float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us"}
-        format = '<Qfff'
-        native_format = bytearray('<Qfff', 'ascii')
-        orders = [0, 1, 2, 3]
-        lengths = [1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0]
-        crc_extra = 39
-        unpacker = struct.Struct('<Qfff')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, payload_bit_rate, total_bit_rate, load_percent):
-                MAVLink_message.__init__(self, MAVLink_can_stats_tm_message.id, MAVLink_can_stats_tm_message.name)
-                self._fieldnames = MAVLink_can_stats_tm_message.fieldnames
-                self._instance_field = MAVLink_can_stats_tm_message.instance_field
-                self._instance_offset = MAVLink_can_stats_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.payload_bit_rate = payload_bit_rate
-                self.total_bit_rate = total_bit_rate
-                self.load_percent = load_percent
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 39, struct.pack('<Qfff', self.timestamp, self.payload_bit_rate, self.total_bit_rate, self.load_percent), force_mavlink1=force_mavlink1)
+    """
+    Status of CanHandler
+    """
+
+    id = MAVLINK_MSG_ID_CAN_STATS_TM
+    msgname = "CAN_STATS_TM"
+    fieldnames = ["timestamp", "payload_bit_rate", "total_bit_rate", "load_percent"]
+    ordered_fieldnames = ["timestamp", "payload_bit_rate", "total_bit_rate", "load_percent"]
+    fieldtypes = ["uint64_t", "float", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us"}
+    native_format = bytearray(b"<Qfff")
+    orders = [0, 1, 2, 3]
+    lengths = [1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0]
+    crc_extra = 39
+    unpacker = struct.Struct("<Qfff")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, payload_bit_rate: float, total_bit_rate: float, load_percent: float):
+        MAVLink_message.__init__(self, MAVLink_can_stats_tm_message.id, MAVLink_can_stats_tm_message.msgname)
+        self._fieldnames = MAVLink_can_stats_tm_message.fieldnames
+        self._instance_field = MAVLink_can_stats_tm_message.instance_field
+        self._instance_offset = MAVLink_can_stats_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.payload_bit_rate = payload_bit_rate
+        self.total_bit_rate = total_bit_rate
+        self.load_percent = load_percent
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.payload_bit_rate, self.total_bit_rate, self.load_percent), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_can_stats_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_task_stats_tm_message(MAVLink_message):
-        '''
-        Statistics of the Task Scheduler
-        '''
-        id = MAVLINK_MSG_ID_TASK_STATS_TM
-        name = 'TASK_STATS_TM'
-        fieldnames = ['timestamp', 'task_id', 'task_period', 'task_missed_events', 'task_failed_events', 'task_activation_mean', 'task_activation_stddev', 'task_period_mean', 'task_period_stddev', 'task_workload_mean', 'task_workload_stddev']
-        ordered_fieldnames = ['timestamp', 'task_missed_events', 'task_failed_events', 'task_activation_mean', 'task_activation_stddev', 'task_period_mean', 'task_period_stddev', 'task_workload_mean', 'task_workload_stddev', 'task_id', 'task_period']
-        fieldtypes = ['uint64_t', 'uint16_t', 'uint16_t', 'uint32_t', 'uint32_t', 'float', 'float', 'float', 'float', 'float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "task_period": "ns"}
-        format = '<QIIffffffHH'
-        native_format = bytearray('<QIIffffffHH', 'ascii')
-        orders = [0, 9, 10, 1, 2, 3, 4, 5, 6, 7, 8]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 19
-        unpacker = struct.Struct('<QIIffffffHH')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, task_id, task_period, task_missed_events, task_failed_events, task_activation_mean, task_activation_stddev, task_period_mean, task_period_stddev, task_workload_mean, task_workload_stddev):
-                MAVLink_message.__init__(self, MAVLink_task_stats_tm_message.id, MAVLink_task_stats_tm_message.name)
-                self._fieldnames = MAVLink_task_stats_tm_message.fieldnames
-                self._instance_field = MAVLink_task_stats_tm_message.instance_field
-                self._instance_offset = MAVLink_task_stats_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.task_id = task_id
-                self.task_period = task_period
-                self.task_missed_events = task_missed_events
-                self.task_failed_events = task_failed_events
-                self.task_activation_mean = task_activation_mean
-                self.task_activation_stddev = task_activation_stddev
-                self.task_period_mean = task_period_mean
-                self.task_period_stddev = task_period_stddev
-                self.task_workload_mean = task_workload_mean
-                self.task_workload_stddev = task_workload_stddev
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 19, struct.pack('<QIIffffffHH', self.timestamp, self.task_missed_events, self.task_failed_events, self.task_activation_mean, self.task_activation_stddev, self.task_period_mean, self.task_period_stddev, self.task_workload_mean, self.task_workload_stddev, self.task_id, self.task_period), force_mavlink1=force_mavlink1)
+    """
+    Statistics of the Task Scheduler
+    """
+
+    id = MAVLINK_MSG_ID_TASK_STATS_TM
+    msgname = "TASK_STATS_TM"
+    fieldnames = ["timestamp", "task_id", "task_period", "task_missed_events", "task_failed_events", "task_activation_mean", "task_activation_stddev", "task_period_mean", "task_period_stddev", "task_workload_mean", "task_workload_stddev"]
+    ordered_fieldnames = ["timestamp", "task_missed_events", "task_failed_events", "task_activation_mean", "task_activation_stddev", "task_period_mean", "task_period_stddev", "task_workload_mean", "task_workload_stddev", "task_id", "task_period"]
+    fieldtypes = ["uint64_t", "uint16_t", "uint16_t", "uint32_t", "uint32_t", "float", "float", "float", "float", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "task_period": "ns"}
+    native_format = bytearray(b"<QIIffffffHH")
+    orders = [0, 9, 10, 1, 2, 3, 4, 5, 6, 7, 8]
+    lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+    crc_extra = 19
+    unpacker = struct.Struct("<QIIffffffHH")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, task_id: int, task_period: int, task_missed_events: int, task_failed_events: int, task_activation_mean: float, task_activation_stddev: float, task_period_mean: float, task_period_stddev: float, task_workload_mean: float, task_workload_stddev: float):
+        MAVLink_message.__init__(self, MAVLink_task_stats_tm_message.id, MAVLink_task_stats_tm_message.msgname)
+        self._fieldnames = MAVLink_task_stats_tm_message.fieldnames
+        self._instance_field = MAVLink_task_stats_tm_message.instance_field
+        self._instance_offset = MAVLink_task_stats_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.task_id = task_id
+        self.task_period = task_period
+        self.task_missed_events = task_missed_events
+        self.task_failed_events = task_failed_events
+        self.task_activation_mean = task_activation_mean
+        self.task_activation_stddev = task_activation_stddev
+        self.task_period_mean = task_period_mean
+        self.task_period_stddev = task_period_stddev
+        self.task_workload_mean = task_workload_mean
+        self.task_workload_stddev = task_workload_stddev
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.task_missed_events, self.task_failed_events, self.task_activation_mean, self.task_activation_stddev, self.task_period_mean, self.task_period_stddev, self.task_workload_mean, self.task_workload_stddev, self.task_id, self.task_period), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_task_stats_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_ada_tm_message(MAVLink_message):
-        '''
-        Apogee Detection Algorithm status telemetry
-        '''
-        id = MAVLINK_MSG_ID_ADA_TM
-        name = 'ADA_TM'
-        fieldnames = ['timestamp', 'state', 'kalman_x0', 'kalman_x1', 'kalman_x2', 'vertical_speed', 'msl_altitude', 'ref_pressure', 'ref_altitude', 'ref_temperature', 'msl_pressure', 'msl_temperature', 'dpl_altitude']
-        ordered_fieldnames = ['timestamp', 'kalman_x0', 'kalman_x1', 'kalman_x2', 'vertical_speed', 'msl_altitude', 'ref_pressure', 'ref_altitude', 'ref_temperature', 'msl_pressure', 'msl_temperature', 'dpl_altitude', 'state']
-        fieldtypes = ['uint64_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "vertical_speed": "m/s", "msl_altitude": "m", "ref_pressure": "Pa", "ref_altitude": "m", "ref_temperature": "degC", "msl_pressure": "Pa", "msl_temperature": "degC", "dpl_altitude": "m"}
-        format = '<QfffffffffffB'
-        native_format = bytearray('<QfffffffffffB', 'ascii')
-        orders = [0, 12, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 234
-        unpacker = struct.Struct('<QfffffffffffB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude):
-                MAVLink_message.__init__(self, MAVLink_ada_tm_message.id, MAVLink_ada_tm_message.name)
-                self._fieldnames = MAVLink_ada_tm_message.fieldnames
-                self._instance_field = MAVLink_ada_tm_message.instance_field
-                self._instance_offset = MAVLink_ada_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.state = state
-                self.kalman_x0 = kalman_x0
-                self.kalman_x1 = kalman_x1
-                self.kalman_x2 = kalman_x2
-                self.vertical_speed = vertical_speed
-                self.msl_altitude = msl_altitude
-                self.ref_pressure = ref_pressure
-                self.ref_altitude = ref_altitude
-                self.ref_temperature = ref_temperature
-                self.msl_pressure = msl_pressure
-                self.msl_temperature = msl_temperature
-                self.dpl_altitude = dpl_altitude
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 234, struct.pack('<QfffffffffffB', self.timestamp, self.kalman_x0, self.kalman_x1, self.kalman_x2, self.vertical_speed, self.msl_altitude, self.ref_pressure, self.ref_altitude, self.ref_temperature, self.msl_pressure, self.msl_temperature, self.dpl_altitude, self.state), force_mavlink1=force_mavlink1)
+    """
+    Apogee Detection Algorithm status telemetry
+    """
+
+    id = MAVLINK_MSG_ID_ADA_TM
+    msgname = "ADA_TM"
+    fieldnames = ["timestamp", "state", "kalman_x0", "kalman_x1", "kalman_x2", "vertical_speed", "msl_altitude", "ref_pressure", "ref_altitude", "ref_temperature", "msl_pressure", "msl_temperature", "dpl_altitude"]
+    ordered_fieldnames = ["timestamp", "kalman_x0", "kalman_x1", "kalman_x2", "vertical_speed", "msl_altitude", "ref_pressure", "ref_altitude", "ref_temperature", "msl_pressure", "msl_temperature", "dpl_altitude", "state"]
+    fieldtypes = ["uint64_t", "uint8_t", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "vertical_speed": "m/s", "msl_altitude": "m", "ref_pressure": "Pa", "ref_altitude": "m", "ref_temperature": "degC", "msl_pressure": "Pa", "msl_temperature": "degC", "dpl_altitude": "m"}
+    native_format = bytearray(b"<QfffffffffffB")
+    orders = [0, 12, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11]
+    lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+    crc_extra = 234
+    unpacker = struct.Struct("<QfffffffffffB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, state: int, kalman_x0: float, kalman_x1: float, kalman_x2: float, vertical_speed: float, msl_altitude: float, ref_pressure: float, ref_altitude: float, ref_temperature: float, msl_pressure: float, msl_temperature: float, dpl_altitude: float):
+        MAVLink_message.__init__(self, MAVLink_ada_tm_message.id, MAVLink_ada_tm_message.msgname)
+        self._fieldnames = MAVLink_ada_tm_message.fieldnames
+        self._instance_field = MAVLink_ada_tm_message.instance_field
+        self._instance_offset = MAVLink_ada_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.state = state
+        self.kalman_x0 = kalman_x0
+        self.kalman_x1 = kalman_x1
+        self.kalman_x2 = kalman_x2
+        self.vertical_speed = vertical_speed
+        self.msl_altitude = msl_altitude
+        self.ref_pressure = ref_pressure
+        self.ref_altitude = ref_altitude
+        self.ref_temperature = ref_temperature
+        self.msl_pressure = msl_pressure
+        self.msl_temperature = msl_temperature
+        self.dpl_altitude = dpl_altitude
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.kalman_x0, self.kalman_x1, self.kalman_x2, self.vertical_speed, self.msl_altitude, self.ref_pressure, self.ref_altitude, self.ref_temperature, self.msl_pressure, self.msl_temperature, self.dpl_altitude, self.state), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_ada_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_nas_tm_message(MAVLink_message):
-        '''
-        Navigation System status telemetry
-        '''
-        id = MAVLINK_MSG_ID_NAS_TM
-        name = 'NAS_TM'
-        fieldnames = ['timestamp', 'state', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'ref_pressure', 'ref_temperature', 'ref_latitude', 'ref_longitude']
-        ordered_fieldnames = ['timestamp', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'ref_pressure', 'ref_temperature', 'ref_latitude', 'ref_longitude', 'state']
-        fieldtypes = ['uint64_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "ref_pressure": "Pa", "ref_temperature": "degC", "ref_latitude": "deg", "ref_longitude": "deg"}
-        format = '<QfffffffffffffffffB'
-        native_format = bytearray('<QfffffffffffffffffB', 'ascii')
-        orders = [0, 18, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17]
-        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 = 66
-        unpacker = struct.Struct('<QfffffffffffffffffB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, state, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, ref_pressure, ref_temperature, ref_latitude, ref_longitude):
-                MAVLink_message.__init__(self, MAVLink_nas_tm_message.id, MAVLink_nas_tm_message.name)
-                self._fieldnames = MAVLink_nas_tm_message.fieldnames
-                self._instance_field = MAVLink_nas_tm_message.instance_field
-                self._instance_offset = MAVLink_nas_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.state = state
-                self.nas_n = nas_n
-                self.nas_e = nas_e
-                self.nas_d = nas_d
-                self.nas_vn = nas_vn
-                self.nas_ve = nas_ve
-                self.nas_vd = nas_vd
-                self.nas_qx = nas_qx
-                self.nas_qy = nas_qy
-                self.nas_qz = nas_qz
-                self.nas_qw = nas_qw
-                self.nas_bias_x = nas_bias_x
-                self.nas_bias_y = nas_bias_y
-                self.nas_bias_z = nas_bias_z
-                self.ref_pressure = ref_pressure
-                self.ref_temperature = ref_temperature
-                self.ref_latitude = ref_latitude
-                self.ref_longitude = ref_longitude
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 66, struct.pack('<QfffffffffffffffffB', self.timestamp, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.ref_pressure, self.ref_temperature, self.ref_latitude, self.ref_longitude, self.state), force_mavlink1=force_mavlink1)
+    """
+    Navigation System status telemetry
+    """
+
+    id = MAVLINK_MSG_ID_NAS_TM
+    msgname = "NAS_TM"
+    fieldnames = ["timestamp", "state", "nas_n", "nas_e", "nas_d", "nas_vn", "nas_ve", "nas_vd", "nas_qx", "nas_qy", "nas_qz", "nas_qw", "nas_bias_x", "nas_bias_y", "nas_bias_z", "ref_pressure", "ref_temperature", "ref_latitude", "ref_longitude"]
+    ordered_fieldnames = ["timestamp", "nas_n", "nas_e", "nas_d", "nas_vn", "nas_ve", "nas_vd", "nas_qx", "nas_qy", "nas_qz", "nas_qw", "nas_bias_x", "nas_bias_y", "nas_bias_z", "ref_pressure", "ref_temperature", "ref_latitude", "ref_longitude", "state"]
+    fieldtypes = ["uint64_t", "uint8_t", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "ref_pressure": "Pa", "ref_temperature": "degC", "ref_latitude": "deg", "ref_longitude": "deg"}
+    native_format = bytearray(b"<QfffffffffffffffffB")
+    orders = [0, 18, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17]
+    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 = 66
+    unpacker = struct.Struct("<QfffffffffffffffffB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, state: int, nas_n: float, nas_e: float, nas_d: float, nas_vn: float, nas_ve: float, nas_vd: float, nas_qx: float, nas_qy: float, nas_qz: float, nas_qw: float, nas_bias_x: float, nas_bias_y: float, nas_bias_z: float, ref_pressure: float, ref_temperature: float, ref_latitude: float, ref_longitude: float):
+        MAVLink_message.__init__(self, MAVLink_nas_tm_message.id, MAVLink_nas_tm_message.msgname)
+        self._fieldnames = MAVLink_nas_tm_message.fieldnames
+        self._instance_field = MAVLink_nas_tm_message.instance_field
+        self._instance_offset = MAVLink_nas_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.state = state
+        self.nas_n = nas_n
+        self.nas_e = nas_e
+        self.nas_d = nas_d
+        self.nas_vn = nas_vn
+        self.nas_ve = nas_ve
+        self.nas_vd = nas_vd
+        self.nas_qx = nas_qx
+        self.nas_qy = nas_qy
+        self.nas_qz = nas_qz
+        self.nas_qw = nas_qw
+        self.nas_bias_x = nas_bias_x
+        self.nas_bias_y = nas_bias_y
+        self.nas_bias_z = nas_bias_z
+        self.ref_pressure = ref_pressure
+        self.ref_temperature = ref_temperature
+        self.ref_latitude = ref_latitude
+        self.ref_longitude = ref_longitude
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.ref_pressure, self.ref_temperature, self.ref_latitude, self.ref_longitude, self.state), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_nas_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_mea_tm_message(MAVLink_message):
-        '''
-        Mass Estimation Algorithm status telemetry
-        '''
-        id = MAVLINK_MSG_ID_MEA_TM
-        name = 'MEA_TM'
-        fieldnames = ['timestamp', 'state', 'kalman_x0', 'kalman_x1', 'kalman_x2', 'mass', 'corrected_pressure']
-        ordered_fieldnames = ['timestamp', 'kalman_x0', 'kalman_x1', 'kalman_x2', 'mass', 'corrected_pressure', 'state']
-        fieldtypes = ['uint64_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "mass": "kg", "corrected_pressure": "Pa"}
-        format = '<QfffffB'
-        native_format = bytearray('<QfffffB', 'ascii')
-        orders = [0, 6, 1, 2, 3, 4, 5]
-        lengths = [1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 11
-        unpacker = struct.Struct('<QfffffB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure):
-                MAVLink_message.__init__(self, MAVLink_mea_tm_message.id, MAVLink_mea_tm_message.name)
-                self._fieldnames = MAVLink_mea_tm_message.fieldnames
-                self._instance_field = MAVLink_mea_tm_message.instance_field
-                self._instance_offset = MAVLink_mea_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.state = state
-                self.kalman_x0 = kalman_x0
-                self.kalman_x1 = kalman_x1
-                self.kalman_x2 = kalman_x2
-                self.mass = mass
-                self.corrected_pressure = corrected_pressure
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 11, struct.pack('<QfffffB', self.timestamp, self.kalman_x0, self.kalman_x1, self.kalman_x2, self.mass, self.corrected_pressure, self.state), force_mavlink1=force_mavlink1)
+    """
+    Mass Estimation Algorithm status telemetry
+    """
+
+    id = MAVLINK_MSG_ID_MEA_TM
+    msgname = "MEA_TM"
+    fieldnames = ["timestamp", "state", "kalman_x0", "kalman_x1", "kalman_x2", "mass", "corrected_pressure"]
+    ordered_fieldnames = ["timestamp", "kalman_x0", "kalman_x1", "kalman_x2", "mass", "corrected_pressure", "state"]
+    fieldtypes = ["uint64_t", "uint8_t", "float", "float", "float", "float", "float"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "mass": "kg", "corrected_pressure": "Pa"}
+    native_format = bytearray(b"<QfffffB")
+    orders = [0, 6, 1, 2, 3, 4, 5]
+    lengths = [1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0]
+    crc_extra = 11
+    unpacker = struct.Struct("<QfffffB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, state: int, kalman_x0: float, kalman_x1: float, kalman_x2: float, mass: float, corrected_pressure: float):
+        MAVLink_message.__init__(self, MAVLink_mea_tm_message.id, MAVLink_mea_tm_message.msgname)
+        self._fieldnames = MAVLink_mea_tm_message.fieldnames
+        self._instance_field = MAVLink_mea_tm_message.instance_field
+        self._instance_offset = MAVLink_mea_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.state = state
+        self.kalman_x0 = kalman_x0
+        self.kalman_x1 = kalman_x1
+        self.kalman_x2 = kalman_x2
+        self.mass = mass
+        self.corrected_pressure = corrected_pressure
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.kalman_x0, self.kalman_x1, self.kalman_x2, self.mass, self.corrected_pressure, self.state), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_mea_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_rocket_flight_tm_message(MAVLink_message):
-        '''
-        High Rate Telemetry
-        '''
-        id = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM
-        name = 'ROCKET_FLIGHT_TM'
-        fieldnames = ['timestamp', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'battery_voltage', 'cam_battery_voltage', 'temperature', 'payload_can_status', 'motor_can_status', 'rig_can_status']
-        ordered_fieldnames = ['timestamp', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'battery_voltage', 'cam_battery_voltage', 'temperature', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'gps_fix', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'payload_can_status', 'motor_can_status', 'rig_can_status']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "pressure_ada": "Pa", "pressure_digi": "Pa", "pressure_static": "Pa", "pressure_dpl": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "ada_vert_speed": "m/s", "mea_mass": "kg", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "abk_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "battery_voltage": "V", "cam_battery_voltage": "V", "temperature": "degC"}
-        format = '<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBBBBB'
-        native_format = bytearray('<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBBBBB', 'ascii')
-        orders = [0, 38, 39, 40, 41, 42, 43, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 44, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 45, 46, 47, 48, 35, 36, 37, 49, 50, 51]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 168
-        unpacker = struct.Struct('<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBBBBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, temperature, payload_can_status, motor_can_status, rig_can_status):
-                MAVLink_message.__init__(self, MAVLink_rocket_flight_tm_message.id, MAVLink_rocket_flight_tm_message.name)
-                self._fieldnames = MAVLink_rocket_flight_tm_message.fieldnames
-                self._instance_field = MAVLink_rocket_flight_tm_message.instance_field
-                self._instance_offset = MAVLink_rocket_flight_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.ada_state = ada_state
-                self.fmm_state = fmm_state
-                self.dpl_state = dpl_state
-                self.abk_state = abk_state
-                self.nas_state = nas_state
-                self.mea_state = mea_state
-                self.pressure_ada = pressure_ada
-                self.pressure_digi = pressure_digi
-                self.pressure_static = pressure_static
-                self.pressure_dpl = pressure_dpl
-                self.airspeed_pitot = airspeed_pitot
-                self.altitude_agl = altitude_agl
-                self.ada_vert_speed = ada_vert_speed
-                self.mea_mass = mea_mass
-                self.acc_x = acc_x
-                self.acc_y = acc_y
-                self.acc_z = acc_z
-                self.gyro_x = gyro_x
-                self.gyro_y = gyro_y
-                self.gyro_z = gyro_z
-                self.mag_x = mag_x
-                self.mag_y = mag_y
-                self.mag_z = mag_z
-                self.gps_fix = gps_fix
-                self.gps_lat = gps_lat
-                self.gps_lon = gps_lon
-                self.gps_alt = gps_alt
-                self.abk_angle = abk_angle
-                self.nas_n = nas_n
-                self.nas_e = nas_e
-                self.nas_d = nas_d
-                self.nas_vn = nas_vn
-                self.nas_ve = nas_ve
-                self.nas_vd = nas_vd
-                self.nas_qx = nas_qx
-                self.nas_qy = nas_qy
-                self.nas_qz = nas_qz
-                self.nas_qw = nas_qw
-                self.nas_bias_x = nas_bias_x
-                self.nas_bias_y = nas_bias_y
-                self.nas_bias_z = nas_bias_z
-                self.pin_launch = pin_launch
-                self.pin_nosecone = pin_nosecone
-                self.pin_expulsion = pin_expulsion
-                self.cutter_presence = cutter_presence
-                self.battery_voltage = battery_voltage
-                self.cam_battery_voltage = cam_battery_voltage
-                self.temperature = temperature
-                self.payload_can_status = payload_can_status
-                self.motor_can_status = motor_can_status
-                self.rig_can_status = rig_can_status
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 168, struct.pack('<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBBBBB', self.timestamp, self.pressure_ada, self.pressure_digi, self.pressure_static, self.pressure_dpl, self.airspeed_pitot, self.altitude_agl, self.ada_vert_speed, self.mea_mass, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.abk_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.battery_voltage, self.cam_battery_voltage, self.temperature, self.ada_state, self.fmm_state, self.dpl_state, self.abk_state, self.nas_state, self.mea_state, self.gps_fix, self.pin_launch, self.pin_nosecone, self.pin_expulsion, self.cutter_presence, self.payload_can_status, self.motor_can_status, self.rig_can_status), force_mavlink1=force_mavlink1)
+    """
+    High Rate Telemetry
+    """
+
+    id = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM
+    msgname = "ROCKET_FLIGHT_TM"
+    fieldnames = ["timestamp", "ada_state", "fmm_state", "dpl_state", "abk_state", "nas_state", "mea_state", "pressure_ada", "pressure_digi", "pressure_static", "pressure_dpl", "airspeed_pitot", "altitude_agl", "ada_vert_speed", "mea_mass", "acc_x", "acc_y", "acc_z", "gyro_x", "gyro_y", "gyro_z", "mag_x", "mag_y", "mag_z", "gps_fix", "gps_lat", "gps_lon", "gps_alt", "abk_angle", "nas_n", "nas_e", "nas_d", "nas_vn", "nas_ve", "nas_vd", "nas_qx", "nas_qy", "nas_qz", "nas_qw", "nas_bias_x", "nas_bias_y", "nas_bias_z", "pin_launch", "pin_nosecone", "pin_expulsion", "cutter_presence", "battery_voltage", "cam_battery_voltage", "temperature", "payload_can_status", "motor_can_status", "rig_can_status"]
+    ordered_fieldnames = ["timestamp", "pressure_ada", "pressure_digi", "pressure_static", "pressure_dpl", "airspeed_pitot", "altitude_agl", "ada_vert_speed", "mea_mass", "acc_x", "acc_y", "acc_z", "gyro_x", "gyro_y", "gyro_z", "mag_x", "mag_y", "mag_z", "gps_lat", "gps_lon", "gps_alt", "abk_angle", "nas_n", "nas_e", "nas_d", "nas_vn", "nas_ve", "nas_vd", "nas_qx", "nas_qy", "nas_qz", "nas_qw", "nas_bias_x", "nas_bias_y", "nas_bias_z", "battery_voltage", "cam_battery_voltage", "temperature", "ada_state", "fmm_state", "dpl_state", "abk_state", "nas_state", "mea_state", "gps_fix", "pin_launch", "pin_nosecone", "pin_expulsion", "cutter_presence", "payload_can_status", "motor_can_status", "rig_can_status"]
+    fieldtypes = ["uint64_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "uint8_t", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "float", "float", "float", "uint8_t", "uint8_t", "uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "pressure_ada": "Pa", "pressure_digi": "Pa", "pressure_static": "Pa", "pressure_dpl": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "ada_vert_speed": "m/s", "mea_mass": "kg", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "abk_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "battery_voltage": "V", "cam_battery_voltage": "V", "temperature": "degC"}
+    native_format = bytearray(b"<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBBBBB")
+    orders = [0, 38, 39, 40, 41, 42, 43, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 44, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 45, 46, 47, 48, 35, 36, 37, 49, 50, 51]
+    lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+    crc_extra = 168
+    unpacker = struct.Struct("<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBBBBB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, ada_state: int, fmm_state: int, dpl_state: int, abk_state: int, nas_state: int, mea_state: int, pressure_ada: float, pressure_digi: float, pressure_static: float, pressure_dpl: float, airspeed_pitot: float, altitude_agl: float, ada_vert_speed: float, mea_mass: float, acc_x: float, acc_y: float, acc_z: float, gyro_x: float, gyro_y: float, gyro_z: float, mag_x: float, mag_y: float, mag_z: float, gps_fix: int, gps_lat: float, gps_lon: float, gps_alt: float, abk_angle: float, nas_n: float, nas_e: float, nas_d: float, nas_vn: float, nas_ve: float, nas_vd: float, nas_qx: float, nas_qy: float, nas_qz: float, nas_qw: float, nas_bias_x: float, nas_bias_y: float, nas_bias_z: float, pin_launch: int, pin_nosecone: int, pin_expulsion: int, cutter_presence: int, battery_voltage: float, cam_battery_voltage: float, temperature: float, payload_can_status: int, motor_can_status: int, rig_can_status: int):
+        MAVLink_message.__init__(self, MAVLink_rocket_flight_tm_message.id, MAVLink_rocket_flight_tm_message.msgname)
+        self._fieldnames = MAVLink_rocket_flight_tm_message.fieldnames
+        self._instance_field = MAVLink_rocket_flight_tm_message.instance_field
+        self._instance_offset = MAVLink_rocket_flight_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.ada_state = ada_state
+        self.fmm_state = fmm_state
+        self.dpl_state = dpl_state
+        self.abk_state = abk_state
+        self.nas_state = nas_state
+        self.mea_state = mea_state
+        self.pressure_ada = pressure_ada
+        self.pressure_digi = pressure_digi
+        self.pressure_static = pressure_static
+        self.pressure_dpl = pressure_dpl
+        self.airspeed_pitot = airspeed_pitot
+        self.altitude_agl = altitude_agl
+        self.ada_vert_speed = ada_vert_speed
+        self.mea_mass = mea_mass
+        self.acc_x = acc_x
+        self.acc_y = acc_y
+        self.acc_z = acc_z
+        self.gyro_x = gyro_x
+        self.gyro_y = gyro_y
+        self.gyro_z = gyro_z
+        self.mag_x = mag_x
+        self.mag_y = mag_y
+        self.mag_z = mag_z
+        self.gps_fix = gps_fix
+        self.gps_lat = gps_lat
+        self.gps_lon = gps_lon
+        self.gps_alt = gps_alt
+        self.abk_angle = abk_angle
+        self.nas_n = nas_n
+        self.nas_e = nas_e
+        self.nas_d = nas_d
+        self.nas_vn = nas_vn
+        self.nas_ve = nas_ve
+        self.nas_vd = nas_vd
+        self.nas_qx = nas_qx
+        self.nas_qy = nas_qy
+        self.nas_qz = nas_qz
+        self.nas_qw = nas_qw
+        self.nas_bias_x = nas_bias_x
+        self.nas_bias_y = nas_bias_y
+        self.nas_bias_z = nas_bias_z
+        self.pin_launch = pin_launch
+        self.pin_nosecone = pin_nosecone
+        self.pin_expulsion = pin_expulsion
+        self.cutter_presence = cutter_presence
+        self.battery_voltage = battery_voltage
+        self.cam_battery_voltage = cam_battery_voltage
+        self.temperature = temperature
+        self.payload_can_status = payload_can_status
+        self.motor_can_status = motor_can_status
+        self.rig_can_status = rig_can_status
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.pressure_ada, self.pressure_digi, self.pressure_static, self.pressure_dpl, self.airspeed_pitot, self.altitude_agl, self.ada_vert_speed, self.mea_mass, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.abk_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.battery_voltage, self.cam_battery_voltage, self.temperature, self.ada_state, self.fmm_state, self.dpl_state, self.abk_state, self.nas_state, self.mea_state, self.gps_fix, self.pin_launch, self.pin_nosecone, self.pin_expulsion, self.cutter_presence, self.payload_can_status, self.motor_can_status, self.rig_can_status), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_rocket_flight_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_payload_flight_tm_message(MAVLink_message):
-        '''
-        High Rate Telemetry
-        '''
-        id = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM
-        name = 'PAYLOAD_FLIGHT_TM'
-        fieldnames = ['timestamp', 'fmm_state', 'nas_state', 'wes_state', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'pin_nosecone', 'battery_voltage', 'cam_battery_voltage', 'cutter_presence', 'temperature', 'main_can_status', 'motor_can_status', 'rig_can_status']
-        ordered_fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'battery_voltage', 'cam_battery_voltage', 'temperature', 'fmm_state', 'nas_state', 'wes_state', 'gps_fix', 'pin_nosecone', 'cutter_presence', 'main_can_status', 'motor_can_status', 'rig_can_status']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'uint8_t', 'float', 'uint8_t', 'uint8_t', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "pressure_digi": "Pa", "pressure_static": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "left_servo_angle": "deg", "right_servo_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "wes_n": "m/s", "wes_e": "m/s", "battery_voltage": "V", "cam_battery_voltage": "V", "temperature": "degC"}
-        format = '<QffffffffffffffffffffffffffffffffffffBBBBBBBBB'
-        native_format = bytearray('<QffffffffffffffffffffffffffffffffffffBBBBBBBBB', 'ascii')
-        orders = [0, 37, 38, 39, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 40, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 41, 34, 35, 42, 36, 43, 44, 45]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 235
-        unpacker = struct.Struct('<QffffffffffffffffffffffffffffffffffffBBBBBBBBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, cutter_presence, temperature, main_can_status, motor_can_status, rig_can_status):
-                MAVLink_message.__init__(self, MAVLink_payload_flight_tm_message.id, MAVLink_payload_flight_tm_message.name)
-                self._fieldnames = MAVLink_payload_flight_tm_message.fieldnames
-                self._instance_field = MAVLink_payload_flight_tm_message.instance_field
-                self._instance_offset = MAVLink_payload_flight_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.fmm_state = fmm_state
-                self.nas_state = nas_state
-                self.wes_state = wes_state
-                self.pressure_digi = pressure_digi
-                self.pressure_static = pressure_static
-                self.airspeed_pitot = airspeed_pitot
-                self.altitude_agl = altitude_agl
-                self.acc_x = acc_x
-                self.acc_y = acc_y
-                self.acc_z = acc_z
-                self.gyro_x = gyro_x
-                self.gyro_y = gyro_y
-                self.gyro_z = gyro_z
-                self.mag_x = mag_x
-                self.mag_y = mag_y
-                self.mag_z = mag_z
-                self.gps_fix = gps_fix
-                self.gps_lat = gps_lat
-                self.gps_lon = gps_lon
-                self.gps_alt = gps_alt
-                self.left_servo_angle = left_servo_angle
-                self.right_servo_angle = right_servo_angle
-                self.nas_n = nas_n
-                self.nas_e = nas_e
-                self.nas_d = nas_d
-                self.nas_vn = nas_vn
-                self.nas_ve = nas_ve
-                self.nas_vd = nas_vd
-                self.nas_qx = nas_qx
-                self.nas_qy = nas_qy
-                self.nas_qz = nas_qz
-                self.nas_qw = nas_qw
-                self.nas_bias_x = nas_bias_x
-                self.nas_bias_y = nas_bias_y
-                self.nas_bias_z = nas_bias_z
-                self.wes_n = wes_n
-                self.wes_e = wes_e
-                self.pin_nosecone = pin_nosecone
-                self.battery_voltage = battery_voltage
-                self.cam_battery_voltage = cam_battery_voltage
-                self.cutter_presence = cutter_presence
-                self.temperature = temperature
-                self.main_can_status = main_can_status
-                self.motor_can_status = motor_can_status
-                self.rig_can_status = rig_can_status
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 235, struct.pack('<QffffffffffffffffffffffffffffffffffffBBBBBBBBB', self.timestamp, self.pressure_digi, self.pressure_static, self.airspeed_pitot, self.altitude_agl, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.left_servo_angle, self.right_servo_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.wes_n, self.wes_e, self.battery_voltage, self.cam_battery_voltage, self.temperature, self.fmm_state, self.nas_state, self.wes_state, self.gps_fix, self.pin_nosecone, self.cutter_presence, self.main_can_status, self.motor_can_status, self.rig_can_status), force_mavlink1=force_mavlink1)
+    """
+    High Rate Telemetry
+    """
+
+    id = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM
+    msgname = "PAYLOAD_FLIGHT_TM"
+    fieldnames = ["timestamp", "fmm_state", "nas_state", "wes_state", "pressure_digi", "pressure_static", "airspeed_pitot", "altitude_agl", "acc_x", "acc_y", "acc_z", "gyro_x", "gyro_y", "gyro_z", "mag_x", "mag_y", "mag_z", "gps_fix", "gps_lat", "gps_lon", "gps_alt", "left_servo_angle", "right_servo_angle", "nas_n", "nas_e", "nas_d", "nas_vn", "nas_ve", "nas_vd", "nas_qx", "nas_qy", "nas_qz", "nas_qw", "nas_bias_x", "nas_bias_y", "nas_bias_z", "wes_n", "wes_e", "pin_nosecone", "battery_voltage", "cam_battery_voltage", "cutter_presence", "temperature", "main_can_status", "motor_can_status", "rig_can_status"]
+    ordered_fieldnames = ["timestamp", "pressure_digi", "pressure_static", "airspeed_pitot", "altitude_agl", "acc_x", "acc_y", "acc_z", "gyro_x", "gyro_y", "gyro_z", "mag_x", "mag_y", "mag_z", "gps_lat", "gps_lon", "gps_alt", "left_servo_angle", "right_servo_angle", "nas_n", "nas_e", "nas_d", "nas_vn", "nas_ve", "nas_vd", "nas_qx", "nas_qy", "nas_qz", "nas_qw", "nas_bias_x", "nas_bias_y", "nas_bias_z", "wes_n", "wes_e", "battery_voltage", "cam_battery_voltage", "temperature", "fmm_state", "nas_state", "wes_state", "gps_fix", "pin_nosecone", "cutter_presence", "main_can_status", "motor_can_status", "rig_can_status"]
+    fieldtypes = ["uint64_t", "uint8_t", "uint8_t", "uint8_t", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "uint8_t", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "float", "uint8_t", "float", "float", "uint8_t", "float", "uint8_t", "uint8_t", "uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "pressure_digi": "Pa", "pressure_static": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "left_servo_angle": "deg", "right_servo_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "wes_n": "m/s", "wes_e": "m/s", "battery_voltage": "V", "cam_battery_voltage": "V", "temperature": "degC"}
+    native_format = bytearray(b"<QffffffffffffffffffffffffffffffffffffBBBBBBBBB")
+    orders = [0, 37, 38, 39, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 40, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 41, 34, 35, 42, 36, 43, 44, 45]
+    lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+    array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+    crc_extra = 235
+    unpacker = struct.Struct("<QffffffffffffffffffffffffffffffffffffBBBBBBBBB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, fmm_state: int, nas_state: int, wes_state: int, pressure_digi: float, pressure_static: float, airspeed_pitot: float, altitude_agl: float, acc_x: float, acc_y: float, acc_z: float, gyro_x: float, gyro_y: float, gyro_z: float, mag_x: float, mag_y: float, mag_z: float, gps_fix: int, gps_lat: float, gps_lon: float, gps_alt: float, left_servo_angle: float, right_servo_angle: float, nas_n: float, nas_e: float, nas_d: float, nas_vn: float, nas_ve: float, nas_vd: float, nas_qx: float, nas_qy: float, nas_qz: float, nas_qw: float, nas_bias_x: float, nas_bias_y: float, nas_bias_z: float, wes_n: float, wes_e: float, pin_nosecone: int, battery_voltage: float, cam_battery_voltage: float, cutter_presence: int, temperature: float, main_can_status: int, motor_can_status: int, rig_can_status: int):
+        MAVLink_message.__init__(self, MAVLink_payload_flight_tm_message.id, MAVLink_payload_flight_tm_message.msgname)
+        self._fieldnames = MAVLink_payload_flight_tm_message.fieldnames
+        self._instance_field = MAVLink_payload_flight_tm_message.instance_field
+        self._instance_offset = MAVLink_payload_flight_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.fmm_state = fmm_state
+        self.nas_state = nas_state
+        self.wes_state = wes_state
+        self.pressure_digi = pressure_digi
+        self.pressure_static = pressure_static
+        self.airspeed_pitot = airspeed_pitot
+        self.altitude_agl = altitude_agl
+        self.acc_x = acc_x
+        self.acc_y = acc_y
+        self.acc_z = acc_z
+        self.gyro_x = gyro_x
+        self.gyro_y = gyro_y
+        self.gyro_z = gyro_z
+        self.mag_x = mag_x
+        self.mag_y = mag_y
+        self.mag_z = mag_z
+        self.gps_fix = gps_fix
+        self.gps_lat = gps_lat
+        self.gps_lon = gps_lon
+        self.gps_alt = gps_alt
+        self.left_servo_angle = left_servo_angle
+        self.right_servo_angle = right_servo_angle
+        self.nas_n = nas_n
+        self.nas_e = nas_e
+        self.nas_d = nas_d
+        self.nas_vn = nas_vn
+        self.nas_ve = nas_ve
+        self.nas_vd = nas_vd
+        self.nas_qx = nas_qx
+        self.nas_qy = nas_qy
+        self.nas_qz = nas_qz
+        self.nas_qw = nas_qw
+        self.nas_bias_x = nas_bias_x
+        self.nas_bias_y = nas_bias_y
+        self.nas_bias_z = nas_bias_z
+        self.wes_n = wes_n
+        self.wes_e = wes_e
+        self.pin_nosecone = pin_nosecone
+        self.battery_voltage = battery_voltage
+        self.cam_battery_voltage = cam_battery_voltage
+        self.cutter_presence = cutter_presence
+        self.temperature = temperature
+        self.main_can_status = main_can_status
+        self.motor_can_status = motor_can_status
+        self.rig_can_status = rig_can_status
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.pressure_digi, self.pressure_static, self.airspeed_pitot, self.altitude_agl, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.left_servo_angle, self.right_servo_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.wes_n, self.wes_e, self.battery_voltage, self.cam_battery_voltage, self.temperature, self.fmm_state, self.nas_state, self.wes_state, self.gps_fix, self.pin_nosecone, self.cutter_presence, self.main_can_status, self.motor_can_status, self.rig_can_status), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_payload_flight_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_rocket_stats_tm_message(MAVLink_message):
-        '''
-        Low Rate Telemetry
-        '''
-        id = MAVLINK_MSG_ID_ROCKET_STATS_TM
-        name = 'ROCKET_STATS_TM'
-        fieldnames = ['liftoff_ts', 'liftoff_max_acc_ts', 'liftoff_max_acc', 'dpl_ts', 'dpl_max_acc', 'max_z_speed_ts', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'ada_min_pressure', 'dpl_bay_max_pressure', 'cpu_load', 'free_heap', 'log_number', 'writes_failed', 'hil_state']
-        ordered_fieldnames = ['liftoff_ts', 'liftoff_max_acc_ts', 'dpl_ts', 'max_z_speed_ts', 'apogee_ts', 'liftoff_max_acc', 'dpl_max_acc', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'ada_min_pressure', 'dpl_bay_max_pressure', 'cpu_load', 'free_heap', 'writes_failed', 'log_number', 'hil_state']
-        fieldtypes = ['uint64_t', 'uint64_t', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint32_t', 'int16_t', 'int32_t', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"liftoff_ts": "us", "liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "dpl_ts": "us", "dpl_max_acc": "m/s2", "max_z_speed_ts": "us", "max_z_speed": "m/s", "max_airspeed_pitot": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "min_pressure": "Pa", "ada_min_pressure": "Pa", "dpl_bay_max_pressure": "Pa"}
-        format = '<QQQQQffffffffffffIihB'
-        native_format = bytearray('<QQQQQffffffffffffIihB', 'ascii')
-        orders = [0, 1, 5, 2, 6, 3, 7, 8, 9, 4, 10, 11, 12, 13, 14, 15, 16, 17, 19, 18, 20]
-        lengths = [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]
-        crc_extra = 169
-        unpacker = struct.Struct('<QQQQQffffffffffffIihB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_bay_max_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state):
-                MAVLink_message.__init__(self, MAVLink_rocket_stats_tm_message.id, MAVLink_rocket_stats_tm_message.name)
-                self._fieldnames = MAVLink_rocket_stats_tm_message.fieldnames
-                self._instance_field = MAVLink_rocket_stats_tm_message.instance_field
-                self._instance_offset = MAVLink_rocket_stats_tm_message.instance_offset
-                self.liftoff_ts = liftoff_ts
-                self.liftoff_max_acc_ts = liftoff_max_acc_ts
-                self.liftoff_max_acc = liftoff_max_acc
-                self.dpl_ts = dpl_ts
-                self.dpl_max_acc = dpl_max_acc
-                self.max_z_speed_ts = max_z_speed_ts
-                self.max_z_speed = max_z_speed
-                self.max_airspeed_pitot = max_airspeed_pitot
-                self.max_speed_altitude = max_speed_altitude
-                self.apogee_ts = apogee_ts
-                self.apogee_lat = apogee_lat
-                self.apogee_lon = apogee_lon
-                self.apogee_alt = apogee_alt
-                self.min_pressure = min_pressure
-                self.ada_min_pressure = ada_min_pressure
-                self.dpl_bay_max_pressure = dpl_bay_max_pressure
-                self.cpu_load = cpu_load
-                self.free_heap = free_heap
-                self.log_number = log_number
-                self.writes_failed = writes_failed
-                self.hil_state = hil_state
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 169, struct.pack('<QQQQQffffffffffffIihB', self.liftoff_ts, self.liftoff_max_acc_ts, self.dpl_ts, self.max_z_speed_ts, self.apogee_ts, self.liftoff_max_acc, self.dpl_max_acc, self.max_z_speed, self.max_airspeed_pitot, self.max_speed_altitude, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.min_pressure, self.ada_min_pressure, self.dpl_bay_max_pressure, self.cpu_load, self.free_heap, self.writes_failed, self.log_number, self.hil_state), force_mavlink1=force_mavlink1)
+    """
+    Low Rate Telemetry
+    """
+
+    id = MAVLINK_MSG_ID_ROCKET_STATS_TM
+    msgname = "ROCKET_STATS_TM"
+    fieldnames = ["liftoff_ts", "liftoff_max_acc_ts", "liftoff_max_acc", "dpl_ts", "dpl_max_acc", "max_z_speed_ts", "max_z_speed", "max_airspeed_pitot", "max_speed_altitude", "apogee_ts", "apogee_lat", "apogee_lon", "apogee_alt", "min_pressure", "ada_min_pressure", "dpl_bay_max_pressure", "cpu_load", "free_heap", "log_number", "writes_failed", "hil_state"]
+    ordered_fieldnames = ["liftoff_ts", "liftoff_max_acc_ts", "dpl_ts", "max_z_speed_ts", "apogee_ts", "liftoff_max_acc", "dpl_max_acc", "max_z_speed", "max_airspeed_pitot", "max_speed_altitude", "apogee_lat", "apogee_lon", "apogee_alt", "min_pressure", "ada_min_pressure", "dpl_bay_max_pressure", "cpu_load", "free_heap", "writes_failed", "log_number", "hil_state"]
+    fieldtypes = ["uint64_t", "uint64_t", "float", "uint64_t", "float", "uint64_t", "float", "float", "float", "uint64_t", "float", "float", "float", "float", "float", "float", "float", "uint32_t", "int16_t", "int32_t", "uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"liftoff_ts": "us", "liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "dpl_ts": "us", "dpl_max_acc": "m/s2", "max_z_speed_ts": "us", "max_z_speed": "m/s", "max_airspeed_pitot": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "min_pressure": "Pa", "ada_min_pressure": "Pa", "dpl_bay_max_pressure": "Pa"}
+    native_format = bytearray(b"<QQQQQffffffffffffIihB")
+    orders = [0, 1, 5, 2, 6, 3, 7, 8, 9, 4, 10, 11, 12, 13, 14, 15, 16, 17, 19, 18, 20]
+    lengths = [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]
+    crc_extra = 169
+    unpacker = struct.Struct("<QQQQQffffffffffffIihB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, liftoff_ts: int, liftoff_max_acc_ts: int, liftoff_max_acc: float, dpl_ts: int, dpl_max_acc: float, max_z_speed_ts: int, max_z_speed: float, max_airspeed_pitot: float, max_speed_altitude: float, apogee_ts: int, apogee_lat: float, apogee_lon: float, apogee_alt: float, min_pressure: float, ada_min_pressure: float, dpl_bay_max_pressure: float, cpu_load: float, free_heap: int, log_number: int, writes_failed: int, hil_state: int):
+        MAVLink_message.__init__(self, MAVLink_rocket_stats_tm_message.id, MAVLink_rocket_stats_tm_message.msgname)
+        self._fieldnames = MAVLink_rocket_stats_tm_message.fieldnames
+        self._instance_field = MAVLink_rocket_stats_tm_message.instance_field
+        self._instance_offset = MAVLink_rocket_stats_tm_message.instance_offset
+        self.liftoff_ts = liftoff_ts
+        self.liftoff_max_acc_ts = liftoff_max_acc_ts
+        self.liftoff_max_acc = liftoff_max_acc
+        self.dpl_ts = dpl_ts
+        self.dpl_max_acc = dpl_max_acc
+        self.max_z_speed_ts = max_z_speed_ts
+        self.max_z_speed = max_z_speed
+        self.max_airspeed_pitot = max_airspeed_pitot
+        self.max_speed_altitude = max_speed_altitude
+        self.apogee_ts = apogee_ts
+        self.apogee_lat = apogee_lat
+        self.apogee_lon = apogee_lon
+        self.apogee_alt = apogee_alt
+        self.min_pressure = min_pressure
+        self.ada_min_pressure = ada_min_pressure
+        self.dpl_bay_max_pressure = dpl_bay_max_pressure
+        self.cpu_load = cpu_load
+        self.free_heap = free_heap
+        self.log_number = log_number
+        self.writes_failed = writes_failed
+        self.hil_state = hil_state
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.liftoff_ts, self.liftoff_max_acc_ts, self.dpl_ts, self.max_z_speed_ts, self.apogee_ts, self.liftoff_max_acc, self.dpl_max_acc, self.max_z_speed, self.max_airspeed_pitot, self.max_speed_altitude, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.min_pressure, self.ada_min_pressure, self.dpl_bay_max_pressure, self.cpu_load, self.free_heap, self.writes_failed, self.log_number, self.hil_state), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_rocket_stats_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_payload_stats_tm_message(MAVLink_message):
-        '''
-        Low Rate Telemetry
-        '''
-        id = MAVLINK_MSG_ID_PAYLOAD_STATS_TM
-        name = 'PAYLOAD_STATS_TM'
-        fieldnames = ['liftoff_max_acc_ts', 'liftoff_max_acc', 'dpl_ts', 'dpl_max_acc', 'max_z_speed_ts', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'cpu_load', 'free_heap', 'log_number', 'writes_failed', 'hil_state']
-        ordered_fieldnames = ['liftoff_max_acc_ts', 'dpl_ts', 'max_z_speed_ts', 'apogee_ts', 'liftoff_max_acc', 'dpl_max_acc', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'cpu_load', 'free_heap', 'writes_failed', 'log_number', 'hil_state']
-        fieldtypes = ['uint64_t', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'uint32_t', 'int16_t', 'int32_t', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "dpl_ts": "us", "dpl_max_acc": "m/s2", "max_z_speed_ts": "us", "max_z_speed": "m/s", "max_airspeed_pitot": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "min_pressure": "Pa"}
-        format = '<QQQQffffffffffIihB'
-        native_format = bytearray('<QQQQffffffffffIihB', 'ascii')
-        orders = [0, 4, 1, 5, 2, 6, 7, 8, 3, 9, 10, 11, 12, 13, 14, 16, 15, 17]
-        lengths = [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]
-        crc_extra = 236
-        unpacker = struct.Struct('<QQQQffffffffffIihB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state):
-                MAVLink_message.__init__(self, MAVLink_payload_stats_tm_message.id, MAVLink_payload_stats_tm_message.name)
-                self._fieldnames = MAVLink_payload_stats_tm_message.fieldnames
-                self._instance_field = MAVLink_payload_stats_tm_message.instance_field
-                self._instance_offset = MAVLink_payload_stats_tm_message.instance_offset
-                self.liftoff_max_acc_ts = liftoff_max_acc_ts
-                self.liftoff_max_acc = liftoff_max_acc
-                self.dpl_ts = dpl_ts
-                self.dpl_max_acc = dpl_max_acc
-                self.max_z_speed_ts = max_z_speed_ts
-                self.max_z_speed = max_z_speed
-                self.max_airspeed_pitot = max_airspeed_pitot
-                self.max_speed_altitude = max_speed_altitude
-                self.apogee_ts = apogee_ts
-                self.apogee_lat = apogee_lat
-                self.apogee_lon = apogee_lon
-                self.apogee_alt = apogee_alt
-                self.min_pressure = min_pressure
-                self.cpu_load = cpu_load
-                self.free_heap = free_heap
-                self.log_number = log_number
-                self.writes_failed = writes_failed
-                self.hil_state = hil_state
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 236, struct.pack('<QQQQffffffffffIihB', self.liftoff_max_acc_ts, self.dpl_ts, self.max_z_speed_ts, self.apogee_ts, self.liftoff_max_acc, self.dpl_max_acc, self.max_z_speed, self.max_airspeed_pitot, self.max_speed_altitude, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.min_pressure, self.cpu_load, self.free_heap, self.writes_failed, self.log_number, self.hil_state), force_mavlink1=force_mavlink1)
+    """
+    Low Rate Telemetry
+    """
+
+    id = MAVLINK_MSG_ID_PAYLOAD_STATS_TM
+    msgname = "PAYLOAD_STATS_TM"
+    fieldnames = ["liftoff_max_acc_ts", "liftoff_max_acc", "dpl_ts", "dpl_max_acc", "max_z_speed_ts", "max_z_speed", "max_airspeed_pitot", "max_speed_altitude", "apogee_ts", "apogee_lat", "apogee_lon", "apogee_alt", "min_pressure", "cpu_load", "free_heap", "log_number", "writes_failed", "hil_state"]
+    ordered_fieldnames = ["liftoff_max_acc_ts", "dpl_ts", "max_z_speed_ts", "apogee_ts", "liftoff_max_acc", "dpl_max_acc", "max_z_speed", "max_airspeed_pitot", "max_speed_altitude", "apogee_lat", "apogee_lon", "apogee_alt", "min_pressure", "cpu_load", "free_heap", "writes_failed", "log_number", "hil_state"]
+    fieldtypes = ["uint64_t", "float", "uint64_t", "float", "uint64_t", "float", "float", "float", "uint64_t", "float", "float", "float", "float", "float", "uint32_t", "int16_t", "int32_t", "uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "dpl_ts": "us", "dpl_max_acc": "m/s2", "max_z_speed_ts": "us", "max_z_speed": "m/s", "max_airspeed_pitot": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "min_pressure": "Pa"}
+    native_format = bytearray(b"<QQQQffffffffffIihB")
+    orders = [0, 4, 1, 5, 2, 6, 7, 8, 3, 9, 10, 11, 12, 13, 14, 16, 15, 17]
+    lengths = [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]
+    crc_extra = 236
+    unpacker = struct.Struct("<QQQQffffffffffIihB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, liftoff_max_acc_ts: int, liftoff_max_acc: float, dpl_ts: int, dpl_max_acc: float, max_z_speed_ts: int, max_z_speed: float, max_airspeed_pitot: float, max_speed_altitude: float, apogee_ts: int, apogee_lat: float, apogee_lon: float, apogee_alt: float, min_pressure: float, cpu_load: float, free_heap: int, log_number: int, writes_failed: int, hil_state: int):
+        MAVLink_message.__init__(self, MAVLink_payload_stats_tm_message.id, MAVLink_payload_stats_tm_message.msgname)
+        self._fieldnames = MAVLink_payload_stats_tm_message.fieldnames
+        self._instance_field = MAVLink_payload_stats_tm_message.instance_field
+        self._instance_offset = MAVLink_payload_stats_tm_message.instance_offset
+        self.liftoff_max_acc_ts = liftoff_max_acc_ts
+        self.liftoff_max_acc = liftoff_max_acc
+        self.dpl_ts = dpl_ts
+        self.dpl_max_acc = dpl_max_acc
+        self.max_z_speed_ts = max_z_speed_ts
+        self.max_z_speed = max_z_speed
+        self.max_airspeed_pitot = max_airspeed_pitot
+        self.max_speed_altitude = max_speed_altitude
+        self.apogee_ts = apogee_ts
+        self.apogee_lat = apogee_lat
+        self.apogee_lon = apogee_lon
+        self.apogee_alt = apogee_alt
+        self.min_pressure = min_pressure
+        self.cpu_load = cpu_load
+        self.free_heap = free_heap
+        self.log_number = log_number
+        self.writes_failed = writes_failed
+        self.hil_state = hil_state
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.liftoff_max_acc_ts, self.dpl_ts, self.max_z_speed_ts, self.apogee_ts, self.liftoff_max_acc, self.dpl_max_acc, self.max_z_speed, self.max_airspeed_pitot, self.max_speed_altitude, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.min_pressure, self.cpu_load, self.free_heap, self.writes_failed, self.log_number, self.hil_state), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_payload_stats_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_gse_tm_message(MAVLink_message):
-        '''
-        Ground Segment Equipment telemetry
-        '''
-        id = MAVLINK_MSG_ID_GSE_TM
-        name = 'GSE_TM'
-        fieldnames = ['timestamp', 'loadcell_rocket', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'nitrogen_valve_state', 'gmm_state', 'tars_state', 'battery_voltage', 'current_consumption', 'umbilical_current_consumption', 'main_board_status', 'payload_board_status', 'main_can_status', 'payload_can_status', 'motor_can_status', 'log_number', 'writes_failed']
-        ordered_fieldnames = ['timestamp', 'loadcell_rocket', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'battery_voltage', 'current_consumption', 'umbilical_current_consumption', 'writes_failed', 'log_number', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'nitrogen_valve_state', 'gmm_state', 'tars_state', 'main_board_status', 'payload_board_status', 'main_can_status', 'payload_can_status', 'motor_can_status']
-        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'int16_t', 'int32_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "loadcell_rocket": "kg", "loadcell_vessel": "kg", "filling_pressure": "Bar", "vessel_pressure": "Bar", "current_consumption": "A", "umbilical_current_consumption": "A"}
-        format = '<QfffffffihBBBBBBBBBBBB'
-        native_format = bytearray('<QfffffffihBBBBBBBBBBBB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 10, 11, 12, 13, 14, 15, 16, 5, 6, 7, 17, 18, 19, 20, 21, 9, 8]
-        lengths = [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]
-        crc_extra = 246
-        unpacker = struct.Struct('<QfffffffihBBBBBBBBBBBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_status, payload_board_status, main_can_status, payload_can_status, motor_can_status, log_number, writes_failed):
-                MAVLink_message.__init__(self, MAVLink_gse_tm_message.id, MAVLink_gse_tm_message.name)
-                self._fieldnames = MAVLink_gse_tm_message.fieldnames
-                self._instance_field = MAVLink_gse_tm_message.instance_field
-                self._instance_offset = MAVLink_gse_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.loadcell_rocket = loadcell_rocket
-                self.loadcell_vessel = loadcell_vessel
-                self.filling_pressure = filling_pressure
-                self.vessel_pressure = vessel_pressure
-                self.filling_valve_state = filling_valve_state
-                self.venting_valve_state = venting_valve_state
-                self.release_valve_state = release_valve_state
-                self.main_valve_state = main_valve_state
-                self.nitrogen_valve_state = nitrogen_valve_state
-                self.gmm_state = gmm_state
-                self.tars_state = tars_state
-                self.battery_voltage = battery_voltage
-                self.current_consumption = current_consumption
-                self.umbilical_current_consumption = umbilical_current_consumption
-                self.main_board_status = main_board_status
-                self.payload_board_status = payload_board_status
-                self.main_can_status = main_can_status
-                self.payload_can_status = payload_can_status
-                self.motor_can_status = motor_can_status
-                self.log_number = log_number
-                self.writes_failed = writes_failed
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 246, struct.pack('<QfffffffihBBBBBBBBBBBB', self.timestamp, self.loadcell_rocket, self.loadcell_vessel, self.filling_pressure, self.vessel_pressure, self.battery_voltage, self.current_consumption, self.umbilical_current_consumption, self.writes_failed, self.log_number, self.filling_valve_state, self.venting_valve_state, self.release_valve_state, self.main_valve_state, self.nitrogen_valve_state, self.gmm_state, self.tars_state, self.main_board_status, self.payload_board_status, self.main_can_status, self.payload_can_status, self.motor_can_status), force_mavlink1=force_mavlink1)
+    """
+    Ground Segment Equipment telemetry
+    """
+
+    id = MAVLINK_MSG_ID_GSE_TM
+    msgname = "GSE_TM"
+    fieldnames = ["timestamp", "loadcell_rocket", "loadcell_vessel", "filling_pressure", "vessel_pressure", "filling_valve_state", "venting_valve_state", "release_valve_state", "main_valve_state", "nitrogen_valve_state", "gmm_state", "tars_state", "battery_voltage", "current_consumption", "umbilical_current_consumption", "main_board_status", "payload_board_status", "main_can_status", "payload_can_status", "motor_can_status", "log_number", "writes_failed"]
+    ordered_fieldnames = ["timestamp", "loadcell_rocket", "loadcell_vessel", "filling_pressure", "vessel_pressure", "battery_voltage", "current_consumption", "umbilical_current_consumption", "writes_failed", "log_number", "filling_valve_state", "venting_valve_state", "release_valve_state", "main_valve_state", "nitrogen_valve_state", "gmm_state", "tars_state", "main_board_status", "payload_board_status", "main_can_status", "payload_can_status", "motor_can_status"]
+    fieldtypes = ["uint64_t", "float", "float", "float", "float", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "float", "float", "float", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "uint8_t", "int16_t", "int32_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "loadcell_rocket": "kg", "loadcell_vessel": "kg", "filling_pressure": "Bar", "vessel_pressure": "Bar", "current_consumption": "A", "umbilical_current_consumption": "A"}
+    native_format = bytearray(b"<QfffffffihBBBBBBBBBBBB")
+    orders = [0, 1, 2, 3, 4, 10, 11, 12, 13, 14, 15, 16, 5, 6, 7, 17, 18, 19, 20, 21, 9, 8]
+    lengths = [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]
+    crc_extra = 246
+    unpacker = struct.Struct("<QfffffffihBBBBBBBBBBBB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, loadcell_rocket: float, loadcell_vessel: float, filling_pressure: float, vessel_pressure: float, filling_valve_state: int, venting_valve_state: int, release_valve_state: int, main_valve_state: int, nitrogen_valve_state: int, gmm_state: int, tars_state: int, battery_voltage: float, current_consumption: float, umbilical_current_consumption: float, main_board_status: int, payload_board_status: int, main_can_status: int, payload_can_status: int, motor_can_status: int, log_number: int, writes_failed: int):
+        MAVLink_message.__init__(self, MAVLink_gse_tm_message.id, MAVLink_gse_tm_message.msgname)
+        self._fieldnames = MAVLink_gse_tm_message.fieldnames
+        self._instance_field = MAVLink_gse_tm_message.instance_field
+        self._instance_offset = MAVLink_gse_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.loadcell_rocket = loadcell_rocket
+        self.loadcell_vessel = loadcell_vessel
+        self.filling_pressure = filling_pressure
+        self.vessel_pressure = vessel_pressure
+        self.filling_valve_state = filling_valve_state
+        self.venting_valve_state = venting_valve_state
+        self.release_valve_state = release_valve_state
+        self.main_valve_state = main_valve_state
+        self.nitrogen_valve_state = nitrogen_valve_state
+        self.gmm_state = gmm_state
+        self.tars_state = tars_state
+        self.battery_voltage = battery_voltage
+        self.current_consumption = current_consumption
+        self.umbilical_current_consumption = umbilical_current_consumption
+        self.main_board_status = main_board_status
+        self.payload_board_status = payload_board_status
+        self.main_can_status = main_can_status
+        self.payload_can_status = payload_can_status
+        self.motor_can_status = motor_can_status
+        self.log_number = log_number
+        self.writes_failed = writes_failed
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.loadcell_rocket, self.loadcell_vessel, self.filling_pressure, self.vessel_pressure, self.battery_voltage, self.current_consumption, self.umbilical_current_consumption, self.writes_failed, self.log_number, self.filling_valve_state, self.venting_valve_state, self.release_valve_state, self.main_valve_state, self.nitrogen_valve_state, self.gmm_state, self.tars_state, self.main_board_status, self.payload_board_status, self.main_can_status, self.payload_can_status, self.motor_can_status), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_gse_tm_message, "name", mavlink_msg_deprecated_name_property())
+
 
 class MAVLink_motor_tm_message(MAVLink_message):
-        '''
-        Motor rocket telemetry
-        '''
-        id = MAVLINK_MSG_ID_MOTOR_TM
-        name = 'MOTOR_TM'
-        fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'tank_temperature', 'main_valve_state', 'venting_valve_state', 'battery_voltage', 'log_number', 'writes_failed', 'hil_state']
-        ordered_fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'tank_temperature', 'battery_voltage', 'writes_failed', 'log_number', 'main_valve_state', 'venting_valve_state', 'hil_state']
-        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'float', 'int16_t', 'int32_t', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "top_tank_pressure": "Bar", "bottom_tank_pressure": "Bar", "combustion_chamber_pressure": "Bar", "battery_voltage": "V"}
-        format = '<QfffffihBBB'
-        native_format = bytearray('<QfffffihBBB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 8, 9, 5, 7, 6, 10]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 32
-        unpacker = struct.Struct('<QfffffihBBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, writes_failed, hil_state):
-                MAVLink_message.__init__(self, MAVLink_motor_tm_message.id, MAVLink_motor_tm_message.name)
-                self._fieldnames = MAVLink_motor_tm_message.fieldnames
-                self._instance_field = MAVLink_motor_tm_message.instance_field
-                self._instance_offset = MAVLink_motor_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.top_tank_pressure = top_tank_pressure
-                self.bottom_tank_pressure = bottom_tank_pressure
-                self.combustion_chamber_pressure = combustion_chamber_pressure
-                self.tank_temperature = tank_temperature
-                self.main_valve_state = main_valve_state
-                self.venting_valve_state = venting_valve_state
-                self.battery_voltage = battery_voltage
-                self.log_number = log_number
-                self.writes_failed = writes_failed
-                self.hil_state = hil_state
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 32, struct.pack('<QfffffihBBB', self.timestamp, self.top_tank_pressure, self.bottom_tank_pressure, self.combustion_chamber_pressure, self.tank_temperature, self.battery_voltage, self.writes_failed, self.log_number, self.main_valve_state, self.venting_valve_state, self.hil_state), force_mavlink1=force_mavlink1)
-
-
-mavlink_map = {
-        MAVLINK_MSG_ID_PING_TC : MAVLink_ping_tc_message,
-        MAVLINK_MSG_ID_COMMAND_TC : MAVLink_command_tc_message,
-        MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC : MAVLink_system_tm_request_tc_message,
-        MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC : MAVLink_sensor_tm_request_tc_message,
-        MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC : MAVLink_servo_tm_request_tc_message,
-        MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC : MAVLink_set_servo_angle_tc_message,
-        MAVLINK_MSG_ID_RESET_SERVO_TC : MAVLink_reset_servo_tc_message,
-        MAVLINK_MSG_ID_WIGGLE_SERVO_TC : MAVLink_wiggle_servo_tc_message,
-        MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC : MAVLink_set_reference_altitude_tc_message,
-        MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC : MAVLink_set_reference_temperature_tc_message,
-        MAVLINK_MSG_ID_SET_ORIENTATION_TC : MAVLink_set_orientation_tc_message,
-        MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC : MAVLink_set_orientation_quat_tc_message,
-        MAVLINK_MSG_ID_SET_COORDINATES_TC : MAVLink_set_coordinates_tc_message,
-        MAVLINK_MSG_ID_RAW_EVENT_TC : MAVLink_raw_event_tc_message,
-        MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC : MAVLink_set_deployment_altitude_tc_message,
-        MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC : MAVLink_set_target_coordinates_tc_message,
-        MAVLINK_MSG_ID_SET_ALGORITHM_TC : MAVLink_set_algorithm_tc_message,
-        MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC : MAVLink_set_atomic_valve_timing_tc_message,
-        MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC : MAVLink_set_valve_maximum_aperture_tc_message,
-        MAVLINK_MSG_ID_CONRIG_STATE_TC : MAVLink_conrig_state_tc_message,
-        MAVLINK_MSG_ID_SET_IGNITION_TIME_TC : MAVLink_set_ignition_time_tc_message,
-        MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC : MAVLink_set_nitrogen_time_tc_message,
-        MAVLINK_MSG_ID_SET_COOLING_TIME_TC : MAVLink_set_cooling_time_tc_message,
-        MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC : MAVLink_set_stepper_angle_tc_message,
-        MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC : MAVLink_set_stepper_steps_tc_message,
-        MAVLINK_MSG_ID_ACK_TM : MAVLink_ack_tm_message,
-        MAVLINK_MSG_ID_NACK_TM : MAVLink_nack_tm_message,
-        MAVLINK_MSG_ID_WACK_TM : MAVLink_wack_tm_message,
-        MAVLINK_MSG_ID_GPS_TM : MAVLink_gps_tm_message,
-        MAVLINK_MSG_ID_IMU_TM : MAVLink_imu_tm_message,
-        MAVLINK_MSG_ID_PRESSURE_TM : MAVLink_pressure_tm_message,
-        MAVLINK_MSG_ID_ADC_TM : MAVLink_adc_tm_message,
-        MAVLINK_MSG_ID_VOLTAGE_TM : MAVLink_voltage_tm_message,
-        MAVLINK_MSG_ID_CURRENT_TM : MAVLink_current_tm_message,
-        MAVLINK_MSG_ID_TEMP_TM : MAVLink_temp_tm_message,
-        MAVLINK_MSG_ID_LOAD_TM : MAVLink_load_tm_message,
-        MAVLINK_MSG_ID_ATTITUDE_TM : MAVLink_attitude_tm_message,
-        MAVLINK_MSG_ID_SENSOR_STATE_TM : MAVLink_sensor_state_tm_message,
-        MAVLINK_MSG_ID_SERVO_TM : MAVLink_servo_tm_message,
-        MAVLINK_MSG_ID_PIN_TM : MAVLink_pin_tm_message,
-        MAVLINK_MSG_ID_REGISTRY_FLOAT_TM : MAVLink_registry_float_tm_message,
-        MAVLINK_MSG_ID_REGISTRY_INT_TM : MAVLink_registry_int_tm_message,
-        MAVLINK_MSG_ID_REGISTRY_COORD_TM : MAVLink_registry_coord_tm_message,
-        MAVLINK_MSG_ID_ARP_TM : MAVLink_arp_tm_message,
-        MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC : MAVLink_set_antenna_coordinates_arp_tc_message,
-        MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC : MAVLink_set_rocket_coordinates_arp_tc_message,
-        MAVLINK_MSG_ID_SYS_TM : MAVLink_sys_tm_message,
-        MAVLINK_MSG_ID_LOGGER_TM : MAVLink_logger_tm_message,
-        MAVLINK_MSG_ID_MAVLINK_STATS_TM : MAVLink_mavlink_stats_tm_message,
-        MAVLINK_MSG_ID_CAN_STATS_TM : MAVLink_can_stats_tm_message,
-        MAVLINK_MSG_ID_TASK_STATS_TM : MAVLink_task_stats_tm_message,
-        MAVLINK_MSG_ID_ADA_TM : MAVLink_ada_tm_message,
-        MAVLINK_MSG_ID_NAS_TM : MAVLink_nas_tm_message,
-        MAVLINK_MSG_ID_MEA_TM : MAVLink_mea_tm_message,
-        MAVLINK_MSG_ID_ROCKET_FLIGHT_TM : MAVLink_rocket_flight_tm_message,
-        MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM : MAVLink_payload_flight_tm_message,
-        MAVLINK_MSG_ID_ROCKET_STATS_TM : MAVLink_rocket_stats_tm_message,
-        MAVLINK_MSG_ID_PAYLOAD_STATS_TM : MAVLink_payload_stats_tm_message,
-        MAVLINK_MSG_ID_GSE_TM : MAVLink_gse_tm_message,
-        MAVLINK_MSG_ID_MOTOR_TM : MAVLink_motor_tm_message,
+    """
+    Motor rocket telemetry
+    """
+
+    id = MAVLINK_MSG_ID_MOTOR_TM
+    msgname = "MOTOR_TM"
+    fieldnames = ["timestamp", "top_tank_pressure", "bottom_tank_pressure", "combustion_chamber_pressure", "floating_level", "tank_temperature", "main_valve_state", "venting_valve_state", "battery_voltage", "log_number", "writes_failed", "hil_state"]
+    ordered_fieldnames = ["timestamp", "top_tank_pressure", "bottom_tank_pressure", "combustion_chamber_pressure", "tank_temperature", "battery_voltage", "writes_failed", "log_number", "floating_level", "main_valve_state", "venting_valve_state", "hil_state"]
+    fieldtypes = ["uint64_t", "float", "float", "float", "uint8_t", "float", "uint8_t", "uint8_t", "float", "int16_t", "int32_t", "uint8_t"]
+    fielddisplays_by_name: Dict[str, str] = {}
+    fieldenums_by_name: Dict[str, str] = {}
+    fieldunits_by_name: Dict[str, str] = {"timestamp": "us", "top_tank_pressure": "Bar", "bottom_tank_pressure": "Bar", "combustion_chamber_pressure": "Bar", "battery_voltage": "V"}
+    native_format = bytearray(b"<QfffffihBBBB")
+    orders = [0, 1, 2, 3, 8, 4, 9, 10, 5, 7, 6, 11]
+    lengths = [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]
+    crc_extra = 160
+    unpacker = struct.Struct("<QfffffihBBBB")
+    instance_field = None
+    instance_offset = -1
+
+    def __init__(self, timestamp: int, top_tank_pressure: float, bottom_tank_pressure: float, combustion_chamber_pressure: float, floating_level: int, tank_temperature: float, main_valve_state: int, venting_valve_state: int, battery_voltage: float, log_number: int, writes_failed: int, hil_state: int):
+        MAVLink_message.__init__(self, MAVLink_motor_tm_message.id, MAVLink_motor_tm_message.msgname)
+        self._fieldnames = MAVLink_motor_tm_message.fieldnames
+        self._instance_field = MAVLink_motor_tm_message.instance_field
+        self._instance_offset = MAVLink_motor_tm_message.instance_offset
+        self.timestamp = timestamp
+        self.top_tank_pressure = top_tank_pressure
+        self.bottom_tank_pressure = bottom_tank_pressure
+        self.combustion_chamber_pressure = combustion_chamber_pressure
+        self.floating_level = floating_level
+        self.tank_temperature = tank_temperature
+        self.main_valve_state = main_valve_state
+        self.venting_valve_state = venting_valve_state
+        self.battery_voltage = battery_voltage
+        self.log_number = log_number
+        self.writes_failed = writes_failed
+        self.hil_state = hil_state
+
+    def pack(self, mav: "MAVLink", force_mavlink1: bool = False) -> bytes:
+        return self._pack(mav, self.crc_extra, self.unpacker.pack(self.timestamp, self.top_tank_pressure, self.bottom_tank_pressure, self.combustion_chamber_pressure, self.tank_temperature, self.battery_voltage, self.writes_failed, self.log_number, self.floating_level, self.main_valve_state, self.venting_valve_state, self.hil_state), force_mavlink1=force_mavlink1)
+
+
+# Define name on the class for backwards compatibility (it is now msgname).
+# Done with setattr to hide the class variable from mypy.
+setattr(MAVLink_motor_tm_message, "name", mavlink_msg_deprecated_name_property())
+
+
+mavlink_map: Dict[int, Type[MAVLink_message]] = {
+    MAVLINK_MSG_ID_PING_TC: MAVLink_ping_tc_message,
+    MAVLINK_MSG_ID_COMMAND_TC: MAVLink_command_tc_message,
+    MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC: MAVLink_system_tm_request_tc_message,
+    MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC: MAVLink_sensor_tm_request_tc_message,
+    MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC: MAVLink_servo_tm_request_tc_message,
+    MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC: MAVLink_set_servo_angle_tc_message,
+    MAVLINK_MSG_ID_RESET_SERVO_TC: MAVLink_reset_servo_tc_message,
+    MAVLINK_MSG_ID_WIGGLE_SERVO_TC: MAVLink_wiggle_servo_tc_message,
+    MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC: MAVLink_set_reference_altitude_tc_message,
+    MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC: MAVLink_set_reference_temperature_tc_message,
+    MAVLINK_MSG_ID_SET_ORIENTATION_TC: MAVLink_set_orientation_tc_message,
+    MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC: MAVLink_set_orientation_quat_tc_message,
+    MAVLINK_MSG_ID_SET_COORDINATES_TC: MAVLink_set_coordinates_tc_message,
+    MAVLINK_MSG_ID_RAW_EVENT_TC: MAVLink_raw_event_tc_message,
+    MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC: MAVLink_set_deployment_altitude_tc_message,
+    MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC: MAVLink_set_target_coordinates_tc_message,
+    MAVLINK_MSG_ID_SET_ALGORITHM_TC: MAVLink_set_algorithm_tc_message,
+    MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC: MAVLink_set_atomic_valve_timing_tc_message,
+    MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC: MAVLink_set_valve_maximum_aperture_tc_message,
+    MAVLINK_MSG_ID_CONRIG_STATE_TC: MAVLink_conrig_state_tc_message,
+    MAVLINK_MSG_ID_SET_IGNITION_TIME_TC: MAVLink_set_ignition_time_tc_message,
+    MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC: MAVLink_set_nitrogen_time_tc_message,
+    MAVLINK_MSG_ID_SET_COOLING_TIME_TC: MAVLink_set_cooling_time_tc_message,
+    MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC: MAVLink_set_stepper_angle_tc_message,
+    MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC: MAVLink_set_stepper_steps_tc_message,
+    MAVLINK_MSG_ID_ACK_TM: MAVLink_ack_tm_message,
+    MAVLINK_MSG_ID_NACK_TM: MAVLink_nack_tm_message,
+    MAVLINK_MSG_ID_WACK_TM: MAVLink_wack_tm_message,
+    MAVLINK_MSG_ID_GPS_TM: MAVLink_gps_tm_message,
+    MAVLINK_MSG_ID_IMU_TM: MAVLink_imu_tm_message,
+    MAVLINK_MSG_ID_PRESSURE_TM: MAVLink_pressure_tm_message,
+    MAVLINK_MSG_ID_ADC_TM: MAVLink_adc_tm_message,
+    MAVLINK_MSG_ID_VOLTAGE_TM: MAVLink_voltage_tm_message,
+    MAVLINK_MSG_ID_CURRENT_TM: MAVLink_current_tm_message,
+    MAVLINK_MSG_ID_TEMP_TM: MAVLink_temp_tm_message,
+    MAVLINK_MSG_ID_LOAD_TM: MAVLink_load_tm_message,
+    MAVLINK_MSG_ID_ATTITUDE_TM: MAVLink_attitude_tm_message,
+    MAVLINK_MSG_ID_SENSOR_STATE_TM: MAVLink_sensor_state_tm_message,
+    MAVLINK_MSG_ID_SERVO_TM: MAVLink_servo_tm_message,
+    MAVLINK_MSG_ID_PIN_TM: MAVLink_pin_tm_message,
+    MAVLINK_MSG_ID_REGISTRY_FLOAT_TM: MAVLink_registry_float_tm_message,
+    MAVLINK_MSG_ID_REGISTRY_INT_TM: MAVLink_registry_int_tm_message,
+    MAVLINK_MSG_ID_REGISTRY_COORD_TM: MAVLink_registry_coord_tm_message,
+    MAVLINK_MSG_ID_ARP_TM: MAVLink_arp_tm_message,
+    MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC: MAVLink_set_antenna_coordinates_arp_tc_message,
+    MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC: MAVLink_set_rocket_coordinates_arp_tc_message,
+    MAVLINK_MSG_ID_ARP_COMMAND_TC: MAVLink_arp_command_tc_message,
+    MAVLINK_MSG_ID_SYS_TM: MAVLink_sys_tm_message,
+    MAVLINK_MSG_ID_LOGGER_TM: MAVLink_logger_tm_message,
+    MAVLINK_MSG_ID_MAVLINK_STATS_TM: MAVLink_mavlink_stats_tm_message,
+    MAVLINK_MSG_ID_CAN_STATS_TM: MAVLink_can_stats_tm_message,
+    MAVLINK_MSG_ID_TASK_STATS_TM: MAVLink_task_stats_tm_message,
+    MAVLINK_MSG_ID_ADA_TM: MAVLink_ada_tm_message,
+    MAVLINK_MSG_ID_NAS_TM: MAVLink_nas_tm_message,
+    MAVLINK_MSG_ID_MEA_TM: MAVLink_mea_tm_message,
+    MAVLINK_MSG_ID_ROCKET_FLIGHT_TM: MAVLink_rocket_flight_tm_message,
+    MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM: MAVLink_payload_flight_tm_message,
+    MAVLINK_MSG_ID_ROCKET_STATS_TM: MAVLink_rocket_stats_tm_message,
+    MAVLINK_MSG_ID_PAYLOAD_STATS_TM: MAVLink_payload_stats_tm_message,
+    MAVLINK_MSG_ID_GSE_TM: MAVLink_gse_tm_message,
+    MAVLINK_MSG_ID_MOTOR_TM: MAVLink_motor_tm_message,
 }
 
+
 class MAVError(Exception):
-        '''MAVLink error class'''
-        def __init__(self, msg):
-            Exception.__init__(self, msg)
-            self.message = msg
-
-class MAVString(str):
-        '''NUL terminated string'''
-        def __init__(self, s):
-                str.__init__(self)
-        def __str__(self):
-            i = self.find(chr(0))
-            if i == -1:
-                return self[:]
-            return self[0:i]
+    """MAVLink error class"""
+
+    def __init__(self, msg: str) -> None:
+        Exception.__init__(self, msg)
+        self.message = msg
+
 
 class MAVLink_bad_data(MAVLink_message):
-        '''
-        a piece of bad data in a mavlink stream
-        '''
-        def __init__(self, data, reason):
-                MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA')
-                self._fieldnames = ['data', 'reason']
-                self.data = data
-                self.reason = reason
-                self._msgbuf = data
-                self._instance_field = None
-
-        def __str__(self):
-            '''Override the __str__ function from MAVLink_messages because non-printable characters are common in to be the reason for this message to exist.'''
-            return '%s {%s, data:%s}' % (self._type, self.reason, [('%x' % ord(i) if isinstance(i, str) else '%x' % i) for i in self.data])
+    """
+    a piece of bad data in a mavlink stream
+    """
+
+    def __init__(self, data: bytes, reason: str) -> None:
+        MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, "BAD_DATA")
+        self._fieldnames = ["data", "reason"]
+        self.data = data
+        self.reason = reason
+        self._msgbuf = bytearray(data)
+        self._instance_field = None
+
+    def __str__(self) -> str:
+        """Override the __str__ function from MAVLink_messages because non-printable characters are common in to be the reason for this message to exist."""
+        if sys.version_info[0] == 2:
+            hexstr = ["{:x}".format(ord(i)) for i in self.data]
+        else:
+            hexstr = ["{:x}".format(i) for i in self.data]
+        return "%s {%s, data:%s}" % (self._type, self.reason, hexstr)
+
 
 class MAVLink_unknown(MAVLink_message):
-        '''
-        a message that we don't have in the XML used when built
-        '''
-        def __init__(self, msgid, data):
-                MAVLink_message.__init__(self, MAVLINK_MSG_ID_UNKNOWN, 'UNKNOWN_%u' % msgid)
-                self._fieldnames = ['data']
-                self.data = data
-                self._msgbuf = data
-                self._instance_field = None
-
-        def __str__(self):
-            '''Override the __str__ function from MAVLink_messages because non-printable characters are common.'''
-            return '%s {data:%s}' % (self._type, [('%x' % ord(i) if isinstance(i, str) else '%x' % i) for i in self.data])
+    """
+    a message that we don't have in the XML used when built
+    """
+
+    def __init__(self, msgid: int, data: bytes) -> None:
+        MAVLink_message.__init__(self, MAVLINK_MSG_ID_UNKNOWN, "UNKNOWN_%u" % msgid)
+        self._fieldnames = ["data"]
+        self.data = data
+        self._msgbuf = bytearray(data)
+        self._instance_field = None
+
+    def __str__(self) -> str:
+        """Override the __str__ function from MAVLink_messages because non-printable characters are common."""
+        if sys.version_info[0] == 2:
+            hexstr = ["{:x}".format(ord(i)) for i in self.data]
+        else:
+            hexstr = ["{:x}".format(i) for i in self.data]
+        return "%s {data:%s}" % (self._type, hexstr)
+
 
 class MAVLinkSigning(object):
-    '''MAVLink signing state class'''
-    def __init__(self):
-        self.secret_key = None
+    """MAVLink signing state class"""
+
+    def __init__(self) -> None:
+        self.secret_key: Optional[bytes] = None
         self.timestamp = 0
         self.link_id = 0
         self.sign_outgoing = False
-        self.allow_unsigned_callback = None
-        self.stream_timestamps = {}
+        self.allow_unsigned_callback: Optional[Callable[["MAVLink", int], bool]] = None
+        self.stream_timestamps: Dict[Tuple[int, int, int], int] = {}
         self.sig_count = 0
         self.badsig_count = 0
         self.goodsig_count = 0
         self.unsigned_count = 0
         self.reject_count = 0
 
+
 class MAVLink(object):
-        '''MAVLink protocol handling class'''
-        def __init__(self, file, srcSystem=0, srcComponent=0, use_native=False):
-                self.seq = 0
-                self.file = file
-                self.srcSystem = srcSystem
-                self.srcComponent = srcComponent
-                self.callback = None
-                self.callback_args = None
-                self.callback_kwargs = None
-                self.send_callback = None
-                self.send_callback_args = None
-                self.send_callback_kwargs = None
-                self.buf = bytearray()
-                self.buf_index = 0
-                self.expected_length = HEADER_LEN_V1+2
-                self.have_prefix_error = False
-                self.robust_parsing = False
-                self.protocol_marker = 254
-                self.little_endian = True
-                self.crc_extra = True
-                self.sort_fields = True
-                self.total_packets_sent = 0
-                self.total_bytes_sent = 0
-                self.total_packets_received = 0
-                self.total_bytes_received = 0
-                self.total_receive_errors = 0
-                self.startup_time = time.time()
-                self.signing = MAVLinkSigning()
-                if native_supported and (use_native or native_testing or native_force):
-                    print("NOTE: mavnative is currently beta-test code")
-                    self.native = mavnative.NativeConnection(MAVLink_message, mavlink_map)
-                else:
-                    self.native = None
-                if native_testing:
-                    self.test_buf = bytearray()
-                self.mav20_unpacker = struct.Struct('<cBBBBBBHB')
-                self.mav10_unpacker = struct.Struct('<cBBBBB')
-                self.mav20_h3_unpacker = struct.Struct('BBB')
-                self.mav_csum_unpacker = struct.Struct('<H')
-                self.mav_sign_unpacker = struct.Struct('<IH')
-
-        def set_callback(self, callback, *args, **kwargs):
-            self.callback = callback
-            self.callback_args = args
-            self.callback_kwargs = kwargs
-
-        def set_send_callback(self, callback, *args, **kwargs):
-            self.send_callback = callback
-            self.send_callback_args = args
-            self.send_callback_kwargs = kwargs
-
-        def send(self, mavmsg, force_mavlink1=False):
-                '''send a MAVLink message'''
-                buf = mavmsg.pack(self, force_mavlink1=force_mavlink1)
-                self.file.write(buf)
-                self.seq = (self.seq + 1) % 256
-                self.total_packets_sent += 1
-                self.total_bytes_sent += len(buf)
-                if self.send_callback:
-                    self.send_callback(mavmsg, *self.send_callback_args, **self.send_callback_kwargs)
-
-        def buf_len(self):
-            return len(self.buf) - self.buf_index
-
-        def bytes_needed(self):
-            '''return number of bytes needed for next parsing stage'''
-            if self.native:
-                ret = self.native.expected_length - self.buf_len()
-            else:
-                ret = self.expected_length - self.buf_len()
+    """MAVLink protocol handling class"""
 
-            if ret <= 0:
-                return 1
-            return ret
+    def __init__(self, file: Any, srcSystem: int = 0, srcComponent: int = 0, use_native: bool = False) -> None:
+        self.seq = 0
+        self.file = file
+        self.srcSystem = srcSystem
+        self.srcComponent = srcComponent
+        self.callback: Optional[Callable[..., None]] = None
+        self.callback_args: Optional[Iterable[Any]] = None
+        self.callback_kwargs: Optional[Mapping[str, Any]] = None
+        self.send_callback: Optional[Callable[..., None]] = None
+        self.send_callback_args: Optional[Iterable[Any]] = None
+        self.send_callback_kwargs: Optional[Mapping[str, Any]] = None
+        self.buf = bytearray()
+        self.buf_index = 0
+        self.expected_length = HEADER_LEN_V1 + 2
+        self.have_prefix_error = False
+        self.robust_parsing = False
+        self.protocol_marker = 254
+        self.little_endian = True
+        self.crc_extra = True
+        self.sort_fields = True
+        self.total_packets_sent = 0
+        self.total_bytes_sent = 0
+        self.total_packets_received = 0
+        self.total_bytes_received = 0
+        self.total_receive_errors = 0
+        self.startup_time = time.time()
+        self.signing = MAVLinkSigning()
+        self.mav20_unpacker = struct.Struct("<cBBBBBBHB")
+        self.mav10_unpacker = struct.Struct("<cBBBBB")
+        self.mav20_h3_unpacker = struct.Struct("BBB")
+        self.mav_csum_unpacker = struct.Struct("<H")
+        self.mav_sign_unpacker = struct.Struct("<IH")
+
+    def set_callback(self, callback: Callable[..., None], *args: Any, **kwargs: Any) -> None:
+        self.callback = callback
+        self.callback_args = args
+        self.callback_kwargs = kwargs
+
+    def set_send_callback(self, callback: Callable[..., None], *args: Any, **kwargs: Any) -> None:
+        self.send_callback = callback
+        self.send_callback_args = args
+        self.send_callback_kwargs = kwargs
+
+    def send(self, mavmsg: MAVLink_message, force_mavlink1: bool = False) -> None:
+        """send a MAVLink message"""
+        buf = mavmsg.pack(self, force_mavlink1=force_mavlink1)
+        self.file.write(buf)
+        self.seq = (self.seq + 1) % 256
+        self.total_packets_sent += 1
+        self.total_bytes_sent += len(buf)
+        if self.send_callback is not None and self.send_callback_args is not None and self.send_callback_kwargs is not None:
+            self.send_callback(mavmsg, *self.send_callback_args, **self.send_callback_kwargs)
+
+    def buf_len(self) -> int:
+        return len(self.buf) - self.buf_index
+
+    def bytes_needed(self) -> int:
+        """return number of bytes needed for next parsing stage"""
+        ret = self.expected_length - self.buf_len()
+
+        if ret <= 0:
+            return 1
+        return ret
 
-        def __parse_char_native(self, c):
-            '''this method exists only to see in profiling results'''
-            m = self.native.parse_chars(c)
-            return m
+    def __callbacks(self, msg: MAVLink_message) -> None:
+        """this method exists only to make profiling results easier to read"""
+        if self.callback is not None and self.callback_args is not None and self.callback_kwargs is not None:
+            self.callback(msg, *self.callback_args, **self.callback_kwargs)
 
-        def __callbacks(self, msg):
-            '''this method exists only to make profiling results easier to read'''
-            if self.callback:
-                self.callback(msg, *self.callback_args, **self.callback_kwargs)
-
-        def parse_char(self, c):
-            '''input some data bytes, possibly returning a new message'''
-            self.buf.extend(c)
-
-            self.total_bytes_received += len(c)
-
-            if self.native:
-                if native_testing:
-                    self.test_buf.extend(c)
-                    m = self.__parse_char_native(self.test_buf)
-                    m2 = self.__parse_char_legacy()
-                    if m2 != m:
-                        print("Native: %s\nLegacy: %s\n" % (m, m2))
-                        raise Exception('Native vs. Legacy mismatch')
-                else:
-                    m = self.__parse_char_native(self.buf)
-            else:
-                m = self.__parse_char_legacy()
+    def parse_char(self, c: Sequence[int]) -> Optional[MAVLink_message]:
+        """input some data bytes, possibly returning a new message"""
+        self.buf.extend(c)
 
-            if m is not None:
-                self.total_packets_received += 1
-                self.__callbacks(m)
-            else:
-                # XXX The idea here is if we've read something and there's nothing left in
-                # the buffer, reset it to 0 which frees the memory
-                if self.buf_len() == 0 and self.buf_index != 0:
-                    self.buf = bytearray()
-                    self.buf_index = 0
+        self.total_bytes_received += len(c)
 
-            return m
+        m = self.__parse_char_legacy()
 
-        def __parse_char_legacy(self):
-            '''input some data bytes, possibly returning a new message (uses no native code)'''
-            header_len = HEADER_LEN_V1
-            if self.buf_len() >= 1 and self.buf[self.buf_index] == PROTOCOL_MARKER_V2:
-                header_len = HEADER_LEN_V2
-
-            if self.buf_len() >= 1 and self.buf[self.buf_index] != PROTOCOL_MARKER_V1 and self.buf[self.buf_index] != PROTOCOL_MARKER_V2:
-                magic = self.buf[self.buf_index]
-                self.buf_index += 1
-                if self.robust_parsing:
-                    m = MAVLink_bad_data(bytearray([magic]), 'Bad prefix')
-                    self.expected_length = header_len+2
-                    self.total_receive_errors += 1
-                    return m
-                if self.have_prefix_error:
-                    return None
-                self.have_prefix_error = True
+        if m is not None:
+            self.total_packets_received += 1
+            self.__callbacks(m)
+        else:
+            # XXX The idea here is if we've read something and there's nothing left in
+            # the buffer, reset it to 0 which frees the memory
+            if self.buf_len() == 0 and self.buf_index != 0:
+                self.buf = bytearray()
+                self.buf_index = 0
+
+        return m
+
+    def __parse_char_legacy(self) -> Optional[MAVLink_message]:
+        """input some data bytes, possibly returning a new message"""
+        header_len = HEADER_LEN_V1
+        if self.buf_len() >= 1 and self.buf[self.buf_index] == PROTOCOL_MARKER_V2:
+            header_len = HEADER_LEN_V2
+
+        m: Optional[MAVLink_message] = None
+        if self.buf_len() >= 1 and self.buf[self.buf_index] != PROTOCOL_MARKER_V1 and self.buf[self.buf_index] != PROTOCOL_MARKER_V2:
+            magic = self.buf[self.buf_index]
+            self.buf_index += 1
+            if self.robust_parsing:
+                m = MAVLink_bad_data(bytearray([magic]), "Bad prefix")
+                self.expected_length = header_len + 2
                 self.total_receive_errors += 1
-                raise MAVError("invalid MAVLink prefix '%s'" % magic)
-            self.have_prefix_error = False
-            if self.buf_len() >= 3:
-                sbuf = self.buf[self.buf_index:3+self.buf_index]
-                if sys.version_info.major < 3:
-                    sbuf = str(sbuf)
-                (magic, self.expected_length, incompat_flags) = self.mav20_h3_unpacker.unpack(sbuf)
-                if magic == PROTOCOL_MARKER_V2 and (incompat_flags & MAVLINK_IFLAG_SIGNED):
-                        self.expected_length += MAVLINK_SIGNATURE_BLOCK_LEN
-                self.expected_length += header_len + 2
-            if self.expected_length >= (header_len+2) and self.buf_len() >= self.expected_length:
-                mbuf = array.array('B', self.buf[self.buf_index:self.buf_index+self.expected_length])
-                self.buf_index += self.expected_length
-                self.expected_length = header_len+2
-                if self.robust_parsing:
-                    try:
-                        if magic == PROTOCOL_MARKER_V2 and (incompat_flags & ~MAVLINK_IFLAG_SIGNED) != 0:
-                            raise MAVError('invalid incompat_flags 0x%x 0x%x %u' % (incompat_flags, magic, self.expected_length))
-                        m = self.decode(mbuf)
-                    except MAVError as reason:
-                        m = MAVLink_bad_data(mbuf, reason.message)
-                        self.total_receive_errors += 1
-                else:
-                    if magic == PROTOCOL_MARKER_V2 and (incompat_flags & ~MAVLINK_IFLAG_SIGNED) != 0:
-                        raise MAVError('invalid incompat_flags 0x%x 0x%x %u' % (incompat_flags, magic, self.expected_length))
-                    m = self.decode(mbuf)
                 return m
-            return None
-
-        def parse_buffer(self, s):
-            '''input some data bytes, possibly returning a list of new messages'''
-            m = self.parse_char(s)
-            if m is None:
+            if self.have_prefix_error:
                 return None
-            ret = [m]
-            while True:
-                m = self.parse_char("")
-                if m is None:
-                    return ret
-                ret.append(m)
-            return ret
-
-        def check_signature(self, msgbuf, srcSystem, srcComponent):
-            '''check signature on incoming message'''
-            if isinstance(msgbuf, array.array):
+            self.have_prefix_error = True
+            self.total_receive_errors += 1
+            raise MAVError("invalid MAVLink prefix '%s'" % magic)
+        self.have_prefix_error = False
+        if self.buf_len() >= 3:
+            sbuf = self.buf[self.buf_index : 3 + self.buf_index]
+            (magic, self.expected_length, incompat_flags) = cast(
+                Tuple[int, int, int],
+                self.mav20_h3_unpacker.unpack(sbuf),
+            )
+            if magic == PROTOCOL_MARKER_V2 and (incompat_flags & MAVLINK_IFLAG_SIGNED):
+                self.expected_length += MAVLINK_SIGNATURE_BLOCK_LEN
+            self.expected_length += header_len + 2
+        if self.expected_length >= (header_len + 2) and self.buf_len() >= self.expected_length:
+            mbuf = self.buf[self.buf_index : self.buf_index + self.expected_length]
+            self.buf_index += self.expected_length
+            self.expected_length = header_len + 2
+            if self.robust_parsing:
                 try:
-                    msgbuf = msgbuf.tostring()
-                except:
-                    msgbuf = msgbuf.tobytes()
-            timestamp_buf = msgbuf[-12:-6]
-            link_id = msgbuf[-13]
-            (tlow, thigh) = self.mav_sign_unpacker.unpack(timestamp_buf)
-            timestamp = tlow + (thigh<<32)
-
-            # see if the timestamp is acceptable
-            stream_key = (link_id,srcSystem,srcComponent)
-            if stream_key in self.signing.stream_timestamps:
-                if timestamp <= self.signing.stream_timestamps[stream_key]:
-                    # reject old timestamp
-                    # print('old timestamp')
-                    return False
-            else:
-                # a new stream has appeared. Accept the timestamp if it is at most
-                # one minute behind our current timestamp
-                if timestamp + 6000*1000 < self.signing.timestamp:
-                    # print('bad new stream ', timestamp/(100.0*1000*60*60*24*365), self.signing.timestamp/(100.0*1000*60*60*24*365))
-                    return False
-                self.signing.stream_timestamps[stream_key] = timestamp
-                # print('new stream')
-
-            h = hashlib.new('sha256')
-            h.update(self.signing.secret_key)
-            h.update(msgbuf[:-6])
-            if str(type(msgbuf)) == "<class 'bytes'>" or str(type(msgbuf)) == "<class 'bytearray'>":
-                # Python 3
-                sig1 = h.digest()[:6]
-                sig2 = msgbuf[-6:]
+                    if magic == PROTOCOL_MARKER_V2 and (incompat_flags & ~MAVLINK_IFLAG_SIGNED) != 0:
+                        raise MAVError("invalid incompat_flags 0x%x 0x%x %u" % (incompat_flags, magic, self.expected_length))
+                    m = self.decode(mbuf)
+                except MAVError as reason:
+                    m = MAVLink_bad_data(mbuf, reason.message)
+                    self.total_receive_errors += 1
             else:
-                sig1 = str(h.digest())[:6]
-                sig2 = str(msgbuf)[-6:]
-            if sig1 != sig2:
-                # print('sig mismatch')
+                if magic == PROTOCOL_MARKER_V2 and (incompat_flags & ~MAVLINK_IFLAG_SIGNED) != 0:
+                    raise MAVError("invalid incompat_flags 0x%x 0x%x %u" % (incompat_flags, magic, self.expected_length))
+                m = self.decode(mbuf)
+            return m
+        return None
+
+    def parse_buffer(self, s: Sequence[int]) -> Optional[List[MAVLink_message]]:
+        """input some data bytes, possibly returning a list of new messages"""
+        m = self.parse_char(s)
+        if m is None:
+            return None
+        ret = [m]
+        while True:
+            m = self.parse_char(b"")
+            if m is None:
+                return ret
+            ret.append(m)
+
+    def check_signature(self, msgbuf: bytearray, srcSystem: int, srcComponent: int) -> bool:
+        """check signature on incoming message"""
+        assert self.signing.secret_key is not None
+
+        timestamp_buf = msgbuf[-12:-6]
+        link_id = msgbuf[-13]
+        (tlow, thigh) = cast(
+            Tuple[int, int],
+            self.mav_sign_unpacker.unpack(timestamp_buf),
+        )
+        timestamp = tlow + (thigh << 32)
+
+        # see if the timestamp is acceptable
+        stream_key = (link_id, srcSystem, srcComponent)
+        if stream_key in self.signing.stream_timestamps:
+            if timestamp <= self.signing.stream_timestamps[stream_key]:
+                # reject old timestamp
+                logger.info("old timestamp")
                 return False
+        else:
+            # a new stream has appeared. Accept the timestamp if it is at most
+            # one minute behind our current timestamp
+            if timestamp + 6000 * 1000 < self.signing.timestamp:
+                logger.info("bad new stream %s %s", timestamp / (100.0 * 1000 * 60 * 60 * 24 * 365), self.signing.timestamp / (100.0 * 1000 * 60 * 60 * 24 * 365))
+                return False
+            self.signing.stream_timestamps[stream_key] = timestamp
+            logger.info("new stream")
+
+        h = hashlib.new("sha256")
+        h.update(self.signing.secret_key)
+        h.update(msgbuf[:-6])
+        sig1 = h.digest()[:6]
+        sig2 = msgbuf[-6:]
+        if sig1 != sig2:
+            logger.info("sig mismatch")
+            return False
 
-            # the timestamp we next send with is the max of the received timestamp and
-            # our current timestamp
-            self.signing.timestamp = max(self.signing.timestamp, timestamp)
-            return True
-
-        def decode(self, msgbuf):
-                '''decode a buffer as a MAVLink message'''
-                # decode the header
-                if msgbuf[0] != PROTOCOL_MARKER_V1:
-                    headerlen = 10
-                    try:
-                        magic, mlen, incompat_flags, compat_flags, seq, srcSystem, srcComponent, msgIdlow, msgIdhigh = self.mav20_unpacker.unpack(msgbuf[:headerlen])
-                    except struct.error as emsg:
-                        raise MAVError('Unable to unpack MAVLink header: %s' % emsg)
-                    msgId = msgIdlow | (msgIdhigh<<16)
-                    mapkey = msgId
+        # the timestamp we next send with is the max of the received timestamp and
+        # our current timestamp
+        self.signing.timestamp = max(self.signing.timestamp, timestamp)
+        return True
+
+    def decode(self, msgbuf: bytearray) -> MAVLink_message:
+        """decode a buffer as a MAVLink message"""
+        # decode the header
+        if msgbuf[0] != PROTOCOL_MARKER_V1:
+            headerlen = 10
+            try:
+                magic, mlen, incompat_flags, compat_flags, seq, srcSystem, srcComponent, msgIdlow, msgIdhigh = cast(
+                    Tuple[bytes, int, int, int, int, int, int, int, int],
+                    self.mav20_unpacker.unpack(msgbuf[:headerlen]),
+                )
+            except struct.error as emsg:
+                raise MAVError("Unable to unpack MAVLink header: %s" % emsg)
+            msgId = msgIdlow | (msgIdhigh << 16)
+            mapkey = msgId
+        else:
+            headerlen = 6
+            try:
+                magic, mlen, seq, srcSystem, srcComponent, msgId = cast(
+                    Tuple[bytes, int, int, int, int, int],
+                    self.mav10_unpacker.unpack(msgbuf[:headerlen]),
+                )
+                incompat_flags = 0
+                compat_flags = 0
+            except struct.error as emsg:
+                raise MAVError("Unable to unpack MAVLink header: %s" % emsg)
+            mapkey = msgId
+        if (incompat_flags & MAVLINK_IFLAG_SIGNED) != 0:
+            signature_len = MAVLINK_SIGNATURE_BLOCK_LEN
+        else:
+            signature_len = 0
+
+        if ord(magic) != PROTOCOL_MARKER_V1 and ord(magic) != PROTOCOL_MARKER_V2:
+            raise MAVError("invalid MAVLink prefix '{}'".format(hex(ord(magic))))
+        if mlen != len(msgbuf) - (headerlen + 2 + signature_len):
+            raise MAVError("invalid MAVLink message length. Got %u expected %u, msgId=%u headerlen=%u" % (len(msgbuf) - (headerlen + 2 + signature_len), mlen, msgId, headerlen))
+
+        if mapkey not in mavlink_map:
+            return MAVLink_unknown(msgId, msgbuf)
+
+        # decode the payload
+        msgtype = mavlink_map[mapkey]
+        order_map = msgtype.orders
+        len_map = msgtype.lengths
+        crc_extra = msgtype.crc_extra
+
+        # decode the checksum
+        try:
+            (crc,) = cast(
+                Tuple[int],
+                self.mav_csum_unpacker.unpack(msgbuf[-(2 + signature_len) :][:2]),
+            )
+        except struct.error as emsg:
+            raise MAVError("Unable to unpack MAVLink CRC: %s" % emsg)
+        crcbuf = msgbuf[1 : -(2 + signature_len)]
+        if True:
+            # using CRC extra
+            crcbuf.append(crc_extra)
+        crc2 = x25crc(crcbuf)
+        if crc != crc2.crc and not MAVLINK_IGNORE_CRC:
+            raise MAVError("invalid MAVLink CRC in msgID %u 0x%04x should be 0x%04x" % (msgId, crc, crc2.crc))
+
+        sig_ok = False
+        if signature_len == MAVLINK_SIGNATURE_BLOCK_LEN:
+            self.signing.sig_count += 1
+        if self.signing.secret_key is not None:
+            accept_signature = False
+            if signature_len == MAVLINK_SIGNATURE_BLOCK_LEN:
+                sig_ok = self.check_signature(msgbuf, srcSystem, srcComponent)
+                accept_signature = sig_ok
+                if sig_ok:
+                    self.signing.goodsig_count += 1
                 else:
-                    headerlen = 6
-                    try:
-                        magic, mlen, seq, srcSystem, srcComponent, msgId = self.mav10_unpacker.unpack(msgbuf[:headerlen])
-                        incompat_flags = 0
-                        compat_flags = 0
-                    except struct.error as emsg:
-                        raise MAVError('Unable to unpack MAVLink header: %s' % emsg)
-                    mapkey = msgId
-                if (incompat_flags & MAVLINK_IFLAG_SIGNED) != 0:
-                    signature_len = MAVLINK_SIGNATURE_BLOCK_LEN
+                    self.signing.badsig_count += 1
+                if not accept_signature and self.signing.allow_unsigned_callback is not None:
+                    accept_signature = self.signing.allow_unsigned_callback(self, msgId)
+                    if accept_signature:
+                        self.signing.unsigned_count += 1
+                    else:
+                        self.signing.reject_count += 1
+            elif self.signing.allow_unsigned_callback is not None:
+                accept_signature = self.signing.allow_unsigned_callback(self, msgId)
+                if accept_signature:
+                    self.signing.unsigned_count += 1
                 else:
-                    signature_len = 0
+                    self.signing.reject_count += 1
+            if not accept_signature:
+                raise MAVError("Invalid signature")
+
+        csize = msgtype.unpacker.size
+        mbuf = msgbuf[headerlen : -(2 + signature_len)]
+        if len(mbuf) < csize:
+            # zero pad to give right size
+            mbuf.extend([0] * (csize - len(mbuf)))
+        if len(mbuf) < csize:
+            raise MAVError("Bad message of type %s length %u needs %s" % (msgtype, len(mbuf), csize))
+        mbuf = mbuf[:csize]
+        try:
+            t = cast(
+                Tuple[Union[bytes, int, float], ...],
+                msgtype.unpacker.unpack(mbuf),
+            )
+        except struct.error as emsg:
+            raise MAVError("Unable to unpack MAVLink payload type=%s payloadLength=%u: %s" % (msgtype, len(mbuf), emsg))
+
+        tlist: List[Union[bytes, float, int, Sequence[float], Sequence[int]]] = list(t)
+        # handle sorted fields
+        if True:
+            if sum(len_map) == len(len_map):
+                # message has no arrays in it
+                for i in range(0, len(tlist)):
+                    tlist[i] = t[order_map[i]]
+            else:
+                # message has some arrays
+                tlist = []
+                for i in range(0, len(order_map)):
+                    order = order_map[i]
+                    L = len_map[order]
+                    tip = sum(len_map[:order])
+                    field = t[tip]
+                    if L == 1 or isinstance(field, bytes):
+                        tlist.append(field)
+                    else:
+                        tlist.append(cast(Union[Sequence[int], Sequence[float]], list(t[tip : (tip + L)])))
+
+        # terminate any strings
+        for i, elem in enumerate(tlist):
+            if isinstance(elem, bytes):
+                tlist[i] = elem.rstrip(b"\x00")
+
+        # construct the message object
+        try:
+            # Note that initializers don't follow the Liskov Substitution Principle
+            # therefore it can't be typechecked
+            m = msgtype(*tlist)  # type: ignore
+        except Exception as emsg:
+            raise MAVError("Unable to instantiate MAVLink message of type %s : %s" % (msgtype, emsg))
+        m._signed = sig_ok
+        if m._signed:
+            m._link_id = msgbuf[-13]
+        m._msgbuf = msgbuf
+        m._payload = msgbuf[6 : -(2 + signature_len)]
+        m._crc = crc
+        m._header = MAVLink_header(msgId, incompat_flags, compat_flags, mlen, seq, srcSystem, srcComponent)
+        return m
+
+    def ping_tc_encode(self, timestamp: int) -> MAVLink_ping_tc_message:
+        """
+        TC to ping the rocket (expects an ACK message as a response)
 
-                if ord(magic) != PROTOCOL_MARKER_V1 and ord(magic) != PROTOCOL_MARKER_V2:
-                    raise MAVError("invalid MAVLink prefix '%s'" % magic)
-                if mlen != len(msgbuf)-(headerlen+2+signature_len):
-                    raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u headerlen=%u' % (len(msgbuf)-(headerlen+2+signature_len), mlen, msgId, headerlen))
+        timestamp                 : Timestamp to identify when it was sent (type:uint64_t)
 
-                if not mapkey in mavlink_map:
-                    return MAVLink_unknown(msgId, msgbuf)
+        """
+        return MAVLink_ping_tc_message(timestamp)
 
-                # decode the payload
-                type = mavlink_map[mapkey]
-                fmt = type.format
-                order_map = type.orders
-                len_map = type.lengths
-                crc_extra = type.crc_extra
+    def ping_tc_send(self, timestamp: int, force_mavlink1: bool = False) -> None:
+        """
+        TC to ping the rocket (expects an ACK message as a response)
 
-                # decode the checksum
-                try:
-                    crc, = self.mav_csum_unpacker.unpack(msgbuf[-(2+signature_len):][:2])
-                except struct.error as emsg:
-                    raise MAVError('Unable to unpack MAVLink CRC: %s' % emsg)
-                crcbuf = msgbuf[1:-(2+signature_len)]
-                if True: # using CRC extra
-                    crcbuf.append(crc_extra)
-                crc2 = x25crc(crcbuf)
-                if crc != crc2.crc and not MAVLINK_IGNORE_CRC:
-                    raise MAVError('invalid MAVLink CRC in msgID %u 0x%04x should be 0x%04x' % (msgId, crc, crc2.crc))
-
-                sig_ok = False
-                if signature_len == MAVLINK_SIGNATURE_BLOCK_LEN:
-                    self.signing.sig_count += 1
-                if self.signing.secret_key is not None:
-                    accept_signature = False
-                    if signature_len == MAVLINK_SIGNATURE_BLOCK_LEN:
-                        sig_ok = self.check_signature(msgbuf, srcSystem, srcComponent)
-                        accept_signature = sig_ok
-                        if sig_ok:
-                            self.signing.goodsig_count += 1
-                        else:
-                            self.signing.badsig_count += 1
-                        if not accept_signature and self.signing.allow_unsigned_callback is not None:
-                            accept_signature = self.signing.allow_unsigned_callback(self, msgId)
-                            if accept_signature:
-                                self.signing.unsigned_count += 1
-                            else:
-                                self.signing.reject_count += 1
-                    elif self.signing.allow_unsigned_callback is not None:
-                        accept_signature = self.signing.allow_unsigned_callback(self, msgId)
-                        if accept_signature:
-                            self.signing.unsigned_count += 1
-                        else:
-                            self.signing.reject_count += 1
-                    if not accept_signature:
-                        raise MAVError('Invalid signature')
-
-                csize = type.unpacker.size
-                mbuf = msgbuf[headerlen:-(2+signature_len)]
-                if len(mbuf) < csize:
-                    # zero pad to give right size
-                    mbuf.extend([0]*(csize - len(mbuf)))
-                if len(mbuf) < csize:
-                    raise MAVError('Bad message of type %s length %u needs %s' % (
-                        type, len(mbuf), csize))
-                mbuf = mbuf[:csize]
-                try:
-                    t = type.unpacker.unpack(mbuf)
-                except struct.error as emsg:
-                    raise MAVError('Unable to unpack MAVLink payload type=%s fmt=%s payloadLength=%u: %s' % (
-                        type, fmt, len(mbuf), emsg))
-
-                tlist = list(t)
-                # handle sorted fields
-                if True:
-                    t = tlist[:]
-                    if sum(len_map) == len(len_map):
-                        # message has no arrays in it
-                        for i in range(0, len(tlist)):
-                            tlist[i] = t[order_map[i]]
-                    else:
-                        # message has some arrays
-                        tlist = []
-                        for i in range(0, len(order_map)):
-                            order = order_map[i]
-                            L = len_map[order]
-                            tip = sum(len_map[:order])
-                            field = t[tip]
-                            if L == 1 or isinstance(field, str):
-                                tlist.append(field)
-                            else:
-                                tlist.append(t[tip:(tip + L)])
-
-                # terminate any strings
-                for i in range(0, len(tlist)):
-                    if type.fieldtypes[i] == 'char':
-                        if sys.version_info.major >= 3:
-                            tlist[i] = to_string(tlist[i])
-                        tlist[i] = str(MAVString(tlist[i]))
-                t = tuple(tlist)
-                # construct the message object
-                try:
-                    m = type(*t)
-                except Exception as emsg:
-                    raise MAVError('Unable to instantiate MAVLink message of type %s : %s' % (type, emsg))
-                m._signed = sig_ok
-                if m._signed:
-                    m._link_id = msgbuf[-13]
-                m._msgbuf = msgbuf
-                m._payload = msgbuf[6:-(2+signature_len)]
-                m._crc = crc
-                m._header = MAVLink_header(msgId, incompat_flags, compat_flags, mlen, seq, srcSystem, srcComponent)
-                return m
-        def ping_tc_encode(self, timestamp):
-                '''
-                TC to ping the rocket (expects an ACK message as a response)
+        timestamp                 : Timestamp to identify when it was sent (type:uint64_t)
 
-                timestamp                 : Timestamp to identify when it was sent (type:uint64_t)
+        """
+        self.send(self.ping_tc_encode(timestamp), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_ping_tc_message(timestamp)
+    def command_tc_encode(self, command_id: int) -> MAVLink_command_tc_message:
+        """
+        TC containing a command with no parameters that trigger some action
 
-        def ping_tc_send(self, timestamp, force_mavlink1=False):
-                '''
-                TC to ping the rocket (expects an ACK message as a response)
+        command_id                : A member of the MavCommandList enum (type:uint8_t)
 
-                timestamp                 : Timestamp to identify when it was sent (type:uint64_t)
+        """
+        return MAVLink_command_tc_message(command_id)
 
-                '''
-                return self.send(self.ping_tc_encode(timestamp), force_mavlink1=force_mavlink1)
+    def command_tc_send(self, command_id: int, force_mavlink1: bool = False) -> None:
+        """
+        TC containing a command with no parameters that trigger some action
 
-        def command_tc_encode(self, command_id):
-                '''
-                TC containing a command with no parameters that trigger some action
+        command_id                : A member of the MavCommandList enum (type:uint8_t)
 
-                command_id                : A member of the MavCommandList enum (type:uint8_t)
+        """
+        self.send(self.command_tc_encode(command_id), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_command_tc_message(command_id)
+    def system_tm_request_tc_encode(self, tm_id: int) -> MAVLink_system_tm_request_tc_message:
+        """
+        TC containing a request for the status of a board
 
-        def command_tc_send(self, command_id, force_mavlink1=False):
-                '''
-                TC containing a command with no parameters that trigger some action
+        tm_id                     : A member of the SystemTMList enum (type:uint8_t)
 
-                command_id                : A member of the MavCommandList enum (type:uint8_t)
+        """
+        return MAVLink_system_tm_request_tc_message(tm_id)
 
-                '''
-                return self.send(self.command_tc_encode(command_id), force_mavlink1=force_mavlink1)
+    def system_tm_request_tc_send(self, tm_id: int, force_mavlink1: bool = False) -> None:
+        """
+        TC containing a request for the status of a board
 
-        def system_tm_request_tc_encode(self, tm_id):
-                '''
-                TC containing a request for the status of a board
+        tm_id                     : A member of the SystemTMList enum (type:uint8_t)
 
-                tm_id                     : A member of the SystemTMList enum (type:uint8_t)
+        """
+        self.send(self.system_tm_request_tc_encode(tm_id), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_system_tm_request_tc_message(tm_id)
+    def sensor_tm_request_tc_encode(self, sensor_name: int) -> MAVLink_sensor_tm_request_tc_message:
+        """
+        TC containing a request for sensors telemetry
 
-        def system_tm_request_tc_send(self, tm_id, force_mavlink1=False):
-                '''
-                TC containing a request for the status of a board
+        sensor_name               : A member of the SensorTMList enum (type:uint8_t)
 
-                tm_id                     : A member of the SystemTMList enum (type:uint8_t)
+        """
+        return MAVLink_sensor_tm_request_tc_message(sensor_name)
 
-                '''
-                return self.send(self.system_tm_request_tc_encode(tm_id), force_mavlink1=force_mavlink1)
+    def sensor_tm_request_tc_send(self, sensor_name: int, force_mavlink1: bool = False) -> None:
+        """
+        TC containing a request for sensors telemetry
 
-        def sensor_tm_request_tc_encode(self, sensor_name):
-                '''
-                TC containing a request for sensors telemetry
+        sensor_name               : A member of the SensorTMList enum (type:uint8_t)
 
-                sensor_name               : A member of the SensorTMList enum (type:uint8_t)
+        """
+        self.send(self.sensor_tm_request_tc_encode(sensor_name), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_sensor_tm_request_tc_message(sensor_name)
+    def servo_tm_request_tc_encode(self, servo_id: int) -> MAVLink_servo_tm_request_tc_message:
+        """
+        TC containing a request for servo telemetry
 
-        def sensor_tm_request_tc_send(self, sensor_name, force_mavlink1=False):
-                '''
-                TC containing a request for sensors telemetry
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
 
-                sensor_name               : A member of the SensorTMList enum (type:uint8_t)
+        """
+        return MAVLink_servo_tm_request_tc_message(servo_id)
 
-                '''
-                return self.send(self.sensor_tm_request_tc_encode(sensor_name), force_mavlink1=force_mavlink1)
+    def servo_tm_request_tc_send(self, servo_id: int, force_mavlink1: bool = False) -> None:
+        """
+        TC containing a request for servo telemetry
 
-        def servo_tm_request_tc_encode(self, servo_id):
-                '''
-                TC containing a request for servo telemetry
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
+        """
+        self.send(self.servo_tm_request_tc_encode(servo_id), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_servo_tm_request_tc_message(servo_id)
+    def set_servo_angle_tc_encode(self, servo_id: int, angle: float) -> MAVLink_set_servo_angle_tc_message:
+        """
+        Sets the angle of a certain servo
 
-        def servo_tm_request_tc_send(self, servo_id, force_mavlink1=False):
-                '''
-                TC containing a request for servo telemetry
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
+        angle                     : Servo angle in normalized value [0-1] (type:float)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
+        """
+        return MAVLink_set_servo_angle_tc_message(servo_id, angle)
 
-                '''
-                return self.send(self.servo_tm_request_tc_encode(servo_id), force_mavlink1=force_mavlink1)
+    def set_servo_angle_tc_send(self, servo_id: int, angle: float, force_mavlink1: bool = False) -> None:
+        """
+        Sets the angle of a certain servo
 
-        def set_servo_angle_tc_encode(self, servo_id, angle):
-                '''
-                Sets the angle of a certain servo
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
+        angle                     : Servo angle in normalized value [0-1] (type:float)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
-                angle                     : Servo angle in normalized value [0-1] (type:float)
+        """
+        self.send(self.set_servo_angle_tc_encode(servo_id, angle), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_servo_angle_tc_message(servo_id, angle)
+    def reset_servo_tc_encode(self, servo_id: int) -> MAVLink_reset_servo_tc_message:
+        """
+        Resets the specified servo
 
-        def set_servo_angle_tc_send(self, servo_id, angle, force_mavlink1=False):
-                '''
-                Sets the angle of a certain servo
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
-                angle                     : Servo angle in normalized value [0-1] (type:float)
+        """
+        return MAVLink_reset_servo_tc_message(servo_id)
 
-                '''
-                return self.send(self.set_servo_angle_tc_encode(servo_id, angle), force_mavlink1=force_mavlink1)
+    def reset_servo_tc_send(self, servo_id: int, force_mavlink1: bool = False) -> None:
+        """
+        Resets the specified servo
 
-        def reset_servo_tc_encode(self, servo_id):
-                '''
-                Resets the specified servo
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
+        """
+        self.send(self.reset_servo_tc_encode(servo_id), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_reset_servo_tc_message(servo_id)
+    def wiggle_servo_tc_encode(self, servo_id: int) -> MAVLink_wiggle_servo_tc_message:
+        """
+        Wiggles the specified servo
 
-        def reset_servo_tc_send(self, servo_id, force_mavlink1=False):
-                '''
-                Resets the specified servo
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
+        """
+        return MAVLink_wiggle_servo_tc_message(servo_id)
 
-                '''
-                return self.send(self.reset_servo_tc_encode(servo_id), force_mavlink1=force_mavlink1)
+    def wiggle_servo_tc_send(self, servo_id: int, force_mavlink1: bool = False) -> None:
+        """
+        Wiggles the specified servo
 
-        def wiggle_servo_tc_encode(self, servo_id):
-                '''
-                Wiggles the specified servo
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
+        """
+        self.send(self.wiggle_servo_tc_encode(servo_id), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_wiggle_servo_tc_message(servo_id)
+    def set_reference_altitude_tc_encode(self, ref_altitude: float) -> MAVLink_set_reference_altitude_tc_message:
+        """
+        Sets the reference altitude for the altimeter
 
-        def wiggle_servo_tc_send(self, servo_id, force_mavlink1=False):
-                '''
-                Wiggles the specified servo
+        ref_altitude              : Reference altitude [m] (type:float)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
+        """
+        return MAVLink_set_reference_altitude_tc_message(ref_altitude)
 
-                '''
-                return self.send(self.wiggle_servo_tc_encode(servo_id), force_mavlink1=force_mavlink1)
+    def set_reference_altitude_tc_send(self, ref_altitude: float, force_mavlink1: bool = False) -> None:
+        """
+        Sets the reference altitude for the altimeter
 
-        def set_reference_altitude_tc_encode(self, ref_altitude):
-                '''
-                Sets the reference altitude for the altimeter
+        ref_altitude              : Reference altitude [m] (type:float)
 
-                ref_altitude              : Reference altitude [m] (type:float)
+        """
+        self.send(self.set_reference_altitude_tc_encode(ref_altitude), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_reference_altitude_tc_message(ref_altitude)
+    def set_reference_temperature_tc_encode(self, ref_temp: float) -> MAVLink_set_reference_temperature_tc_message:
+        """
+        Sets the reference temperature for the altimeter
 
-        def set_reference_altitude_tc_send(self, ref_altitude, force_mavlink1=False):
-                '''
-                Sets the reference altitude for the altimeter
+        ref_temp                  : Reference temperature [degC] (type:float)
 
-                ref_altitude              : Reference altitude [m] (type:float)
+        """
+        return MAVLink_set_reference_temperature_tc_message(ref_temp)
 
-                '''
-                return self.send(self.set_reference_altitude_tc_encode(ref_altitude), force_mavlink1=force_mavlink1)
+    def set_reference_temperature_tc_send(self, ref_temp: float, force_mavlink1: bool = False) -> None:
+        """
+        Sets the reference temperature for the altimeter
 
-        def set_reference_temperature_tc_encode(self, ref_temp):
-                '''
-                Sets the reference temperature for the altimeter
+        ref_temp                  : Reference temperature [degC] (type:float)
 
-                ref_temp                  : Reference temperature [degC] (type:float)
+        """
+        self.send(self.set_reference_temperature_tc_encode(ref_temp), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_reference_temperature_tc_message(ref_temp)
+    def set_orientation_tc_encode(self, yaw: float, pitch: float, roll: float) -> MAVLink_set_orientation_tc_message:
+        """
+        Sets current orientation for the navigation system
 
-        def set_reference_temperature_tc_send(self, ref_temp, force_mavlink1=False):
-                '''
-                Sets the reference temperature for the altimeter
+        yaw                       : Yaw angle [deg] (type:float)
+        pitch                     : Pitch angle [deg] (type:float)
+        roll                      : Roll angle [deg] (type:float)
 
-                ref_temp                  : Reference temperature [degC] (type:float)
+        """
+        return MAVLink_set_orientation_tc_message(yaw, pitch, roll)
 
-                '''
-                return self.send(self.set_reference_temperature_tc_encode(ref_temp), force_mavlink1=force_mavlink1)
+    def set_orientation_tc_send(self, yaw: float, pitch: float, roll: float, force_mavlink1: bool = False) -> None:
+        """
+        Sets current orientation for the navigation system
 
-        def set_orientation_tc_encode(self, yaw, pitch, roll):
-                '''
-                Sets current orientation for the navigation system
+        yaw                       : Yaw angle [deg] (type:float)
+        pitch                     : Pitch angle [deg] (type:float)
+        roll                      : Roll angle [deg] (type:float)
 
-                yaw                       : Yaw angle [deg] (type:float)
-                pitch                     : Pitch angle [deg] (type:float)
-                roll                      : Roll angle [deg] (type:float)
+        """
+        self.send(self.set_orientation_tc_encode(yaw, pitch, roll), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_orientation_tc_message(yaw, pitch, roll)
+    def set_orientation_quat_tc_encode(self, quat_x: float, quat_y: float, quat_z: float, quat_w: float) -> MAVLink_set_orientation_quat_tc_message:
+        """
+        Sets current orientation for the navigation system using a quaternion
 
-        def set_orientation_tc_send(self, yaw, pitch, roll, force_mavlink1=False):
-                '''
-                Sets current orientation for the navigation system
+        quat_x                    : Quaternion x component (type:float)
+        quat_y                    : Quaternion y component (type:float)
+        quat_z                    : Quaternion z component (type:float)
+        quat_w                    : Quaternion w component (type:float)
 
-                yaw                       : Yaw angle [deg] (type:float)
-                pitch                     : Pitch angle [deg] (type:float)
-                roll                      : Roll angle [deg] (type:float)
+        """
+        return MAVLink_set_orientation_quat_tc_message(quat_x, quat_y, quat_z, quat_w)
 
-                '''
-                return self.send(self.set_orientation_tc_encode(yaw, pitch, roll), force_mavlink1=force_mavlink1)
+    def set_orientation_quat_tc_send(self, quat_x: float, quat_y: float, quat_z: float, quat_w: float, force_mavlink1: bool = False) -> None:
+        """
+        Sets current orientation for the navigation system using a quaternion
 
-        def set_orientation_quat_tc_encode(self, quat_x, quat_y, quat_z, quat_w):
-                '''
-                Sets current orientation for the navigation system using a quaternion
+        quat_x                    : Quaternion x component (type:float)
+        quat_y                    : Quaternion y component (type:float)
+        quat_z                    : Quaternion z component (type:float)
+        quat_w                    : Quaternion w component (type:float)
 
-                quat_x                    : Quaternion x component (type:float)
-                quat_y                    : Quaternion y component (type:float)
-                quat_z                    : Quaternion z component (type:float)
-                quat_w                    : Quaternion w component (type:float)
+        """
+        self.send(self.set_orientation_quat_tc_encode(quat_x, quat_y, quat_z, quat_w), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_orientation_quat_tc_message(quat_x, quat_y, quat_z, quat_w)
+    def set_coordinates_tc_encode(self, latitude: float, longitude: float) -> MAVLink_set_coordinates_tc_message:
+        """
+        Sets current coordinates
 
-        def set_orientation_quat_tc_send(self, quat_x, quat_y, quat_z, quat_w, force_mavlink1=False):
-                '''
-                Sets current orientation for the navigation system using a quaternion
+        latitude                  : Latitude [deg] (type:float)
+        longitude                 : Longitude [deg] (type:float)
 
-                quat_x                    : Quaternion x component (type:float)
-                quat_y                    : Quaternion y component (type:float)
-                quat_z                    : Quaternion z component (type:float)
-                quat_w                    : Quaternion w component (type:float)
+        """
+        return MAVLink_set_coordinates_tc_message(latitude, longitude)
 
-                '''
-                return self.send(self.set_orientation_quat_tc_encode(quat_x, quat_y, quat_z, quat_w), force_mavlink1=force_mavlink1)
+    def set_coordinates_tc_send(self, latitude: float, longitude: float, force_mavlink1: bool = False) -> None:
+        """
+        Sets current coordinates
 
-        def set_coordinates_tc_encode(self, latitude, longitude):
-                '''
-                Sets current coordinates
+        latitude                  : Latitude [deg] (type:float)
+        longitude                 : Longitude [deg] (type:float)
 
-                latitude                  : Latitude [deg] (type:float)
-                longitude                 : Longitude [deg] (type:float)
+        """
+        self.send(self.set_coordinates_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_coordinates_tc_message(latitude, longitude)
+    def raw_event_tc_encode(self, topic_id: int, event_id: int) -> MAVLink_raw_event_tc_message:
+        """
+        TC containing a raw event to be posted directly in the EventBroker
 
-        def set_coordinates_tc_send(self, latitude, longitude, force_mavlink1=False):
-                '''
-                Sets current coordinates
+        topic_id                  : Id of the topic to which the event should be posted (type:uint8_t)
+        event_id                  : Id of the event to be posted (type:uint8_t)
 
-                latitude                  : Latitude [deg] (type:float)
-                longitude                 : Longitude [deg] (type:float)
+        """
+        return MAVLink_raw_event_tc_message(topic_id, event_id)
 
-                '''
-                return self.send(self.set_coordinates_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1)
+    def raw_event_tc_send(self, topic_id: int, event_id: int, force_mavlink1: bool = False) -> None:
+        """
+        TC containing a raw event to be posted directly in the EventBroker
 
-        def raw_event_tc_encode(self, topic_id, event_id):
-                '''
-                TC containing a raw event to be posted directly in the EventBroker
+        topic_id                  : Id of the topic to which the event should be posted (type:uint8_t)
+        event_id                  : Id of the event to be posted (type:uint8_t)
 
-                topic_id                  : Id of the topic to which the event should be posted (type:uint8_t)
-                event_id                  : Id of the event to be posted (type:uint8_t)
+        """
+        self.send(self.raw_event_tc_encode(topic_id, event_id), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_raw_event_tc_message(topic_id, event_id)
+    def set_deployment_altitude_tc_encode(self, dpl_altitude: float) -> MAVLink_set_deployment_altitude_tc_message:
+        """
+        Sets the deployment altitude for the main parachute
 
-        def raw_event_tc_send(self, topic_id, event_id, force_mavlink1=False):
-                '''
-                TC containing a raw event to be posted directly in the EventBroker
+        dpl_altitude              : Deployment altitude [m] (type:float)
 
-                topic_id                  : Id of the topic to which the event should be posted (type:uint8_t)
-                event_id                  : Id of the event to be posted (type:uint8_t)
+        """
+        return MAVLink_set_deployment_altitude_tc_message(dpl_altitude)
 
-                '''
-                return self.send(self.raw_event_tc_encode(topic_id, event_id), force_mavlink1=force_mavlink1)
+    def set_deployment_altitude_tc_send(self, dpl_altitude: float, force_mavlink1: bool = False) -> None:
+        """
+        Sets the deployment altitude for the main parachute
 
-        def set_deployment_altitude_tc_encode(self, dpl_altitude):
-                '''
-                Sets the deployment altitude for the main parachute
+        dpl_altitude              : Deployment altitude [m] (type:float)
 
-                dpl_altitude              : Deployment altitude [m] (type:float)
+        """
+        self.send(self.set_deployment_altitude_tc_encode(dpl_altitude), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_deployment_altitude_tc_message(dpl_altitude)
+    def set_target_coordinates_tc_encode(self, latitude: float, longitude: float) -> MAVLink_set_target_coordinates_tc_message:
+        """
+        Sets the target coordinates
 
-        def set_deployment_altitude_tc_send(self, dpl_altitude, force_mavlink1=False):
-                '''
-                Sets the deployment altitude for the main parachute
+        latitude                  : Latitude [deg] (type:float)
+        longitude                 : Longitude [deg] (type:float)
 
-                dpl_altitude              : Deployment altitude [m] (type:float)
+        """
+        return MAVLink_set_target_coordinates_tc_message(latitude, longitude)
 
-                '''
-                return self.send(self.set_deployment_altitude_tc_encode(dpl_altitude), force_mavlink1=force_mavlink1)
+    def set_target_coordinates_tc_send(self, latitude: float, longitude: float, force_mavlink1: bool = False) -> None:
+        """
+        Sets the target coordinates
 
-        def set_target_coordinates_tc_encode(self, latitude, longitude):
-                '''
-                Sets the target coordinates
+        latitude                  : Latitude [deg] (type:float)
+        longitude                 : Longitude [deg] (type:float)
 
-                latitude                  : Latitude [deg] (type:float)
-                longitude                 : Longitude [deg] (type:float)
+        """
+        self.send(self.set_target_coordinates_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_target_coordinates_tc_message(latitude, longitude)
+    def set_algorithm_tc_encode(self, algorithm_number: int) -> MAVLink_set_algorithm_tc_message:
+        """
+        Sets the algorithm number (for parafoil guidance)
 
-        def set_target_coordinates_tc_send(self, latitude, longitude, force_mavlink1=False):
-                '''
-                Sets the target coordinates
+        algorithm_number          : Algorithm number (type:uint8_t)
 
-                latitude                  : Latitude [deg] (type:float)
-                longitude                 : Longitude [deg] (type:float)
+        """
+        return MAVLink_set_algorithm_tc_message(algorithm_number)
 
-                '''
-                return self.send(self.set_target_coordinates_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1)
+    def set_algorithm_tc_send(self, algorithm_number: int, force_mavlink1: bool = False) -> None:
+        """
+        Sets the algorithm number (for parafoil guidance)
 
-        def set_algorithm_tc_encode(self, algorithm_number):
-                '''
-                Sets the algorithm number (for parafoil guidance)
+        algorithm_number          : Algorithm number (type:uint8_t)
 
-                algorithm_number          : Algorithm number (type:uint8_t)
+        """
+        self.send(self.set_algorithm_tc_encode(algorithm_number), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_algorithm_tc_message(algorithm_number)
+    def set_atomic_valve_timing_tc_encode(self, servo_id: int, maximum_timing: int) -> MAVLink_set_atomic_valve_timing_tc_message:
+        """
+        Sets the maximum time that the valves can be open atomically
 
-        def set_algorithm_tc_send(self, algorithm_number, force_mavlink1=False):
-                '''
-                Sets the algorithm number (for parafoil guidance)
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
+        maximum_timing            : Maximum timing in [ms] [ms] (type:uint32_t)
 
-                algorithm_number          : Algorithm number (type:uint8_t)
+        """
+        return MAVLink_set_atomic_valve_timing_tc_message(servo_id, maximum_timing)
 
-                '''
-                return self.send(self.set_algorithm_tc_encode(algorithm_number), force_mavlink1=force_mavlink1)
+    def set_atomic_valve_timing_tc_send(self, servo_id: int, maximum_timing: int, force_mavlink1: bool = False) -> None:
+        """
+        Sets the maximum time that the valves can be open atomically
 
-        def set_atomic_valve_timing_tc_encode(self, servo_id, maximum_timing):
-                '''
-                Sets the maximum time that the valves can be open atomically
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
+        maximum_timing            : Maximum timing in [ms] [ms] (type:uint32_t)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
-                maximum_timing            : Maximum timing in [ms] [ms] (type:uint32_t)
+        """
+        self.send(self.set_atomic_valve_timing_tc_encode(servo_id, maximum_timing), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_atomic_valve_timing_tc_message(servo_id, maximum_timing)
+    def set_valve_maximum_aperture_tc_encode(self, servo_id: int, maximum_aperture: float) -> MAVLink_set_valve_maximum_aperture_tc_message:
+        """
+        Sets the maximum aperture of the specified valve. Set as value from 0
+        to 1
 
-        def set_atomic_valve_timing_tc_send(self, servo_id, maximum_timing, force_mavlink1=False):
-                '''
-                Sets the maximum time that the valves can be open atomically
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
+        maximum_aperture          : Maximum aperture (type:float)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
-                maximum_timing            : Maximum timing in [ms] [ms] (type:uint32_t)
+        """
+        return MAVLink_set_valve_maximum_aperture_tc_message(servo_id, maximum_aperture)
 
-                '''
-                return self.send(self.set_atomic_valve_timing_tc_encode(servo_id, maximum_timing), force_mavlink1=force_mavlink1)
+    def set_valve_maximum_aperture_tc_send(self, servo_id: int, maximum_aperture: float, force_mavlink1: bool = False) -> None:
+        """
+        Sets the maximum aperture of the specified valve. Set as value from 0
+        to 1
 
-        def set_valve_maximum_aperture_tc_encode(self, servo_id, maximum_aperture):
-                '''
-                Sets the maximum aperture of the specified valve. Set as value from 0
-                to 1
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
+        maximum_aperture          : Maximum aperture (type:float)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
-                maximum_aperture          : Maximum aperture (type:float)
+        """
+        self.send(self.set_valve_maximum_aperture_tc_encode(servo_id, maximum_aperture), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_valve_maximum_aperture_tc_message(servo_id, maximum_aperture)
+    def conrig_state_tc_encode(self, ignition_btn: int, filling_valve_btn: int, venting_valve_btn: int, release_pressure_btn: int, quick_connector_btn: int, start_tars_btn: int, arm_switch: int) -> MAVLink_conrig_state_tc_message:
+        """
+        Send the state of the conrig buttons
 
-        def set_valve_maximum_aperture_tc_send(self, servo_id, maximum_aperture, force_mavlink1=False):
-                '''
-                Sets the maximum aperture of the specified valve. Set as value from 0
-                to 1
+        ignition_btn              : Ignition button pressed (type:uint8_t)
+        filling_valve_btn         : Open filling valve pressed (type:uint8_t)
+        venting_valve_btn         : Open venting valve pressed (type:uint8_t)
+        release_pressure_btn        : Release filling line pressure pressed (type:uint8_t)
+        quick_connector_btn        : Detach quick connector pressed (type:uint8_t)
+        start_tars_btn            : Startup TARS pressed (type:uint8_t)
+        arm_switch                : Arming switch state (type:uint8_t)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
-                maximum_aperture          : Maximum aperture (type:float)
+        """
+        return MAVLink_conrig_state_tc_message(ignition_btn, filling_valve_btn, venting_valve_btn, release_pressure_btn, quick_connector_btn, start_tars_btn, arm_switch)
 
-                '''
-                return self.send(self.set_valve_maximum_aperture_tc_encode(servo_id, maximum_aperture), force_mavlink1=force_mavlink1)
+    def conrig_state_tc_send(self, ignition_btn: int, filling_valve_btn: int, venting_valve_btn: int, release_pressure_btn: int, quick_connector_btn: int, start_tars_btn: int, arm_switch: int, force_mavlink1: bool = False) -> None:
+        """
+        Send the state of the conrig buttons
 
-        def conrig_state_tc_encode(self, ignition_btn, filling_valve_btn, venting_valve_btn, release_pressure_btn, quick_connector_btn, start_tars_btn, arm_switch):
-                '''
-                Send the state of the conrig buttons
+        ignition_btn              : Ignition button pressed (type:uint8_t)
+        filling_valve_btn         : Open filling valve pressed (type:uint8_t)
+        venting_valve_btn         : Open venting valve pressed (type:uint8_t)
+        release_pressure_btn        : Release filling line pressure pressed (type:uint8_t)
+        quick_connector_btn        : Detach quick connector pressed (type:uint8_t)
+        start_tars_btn            : Startup TARS pressed (type:uint8_t)
+        arm_switch                : Arming switch state (type:uint8_t)
 
-                ignition_btn              : Ignition button pressed (type:uint8_t)
-                filling_valve_btn         : Open filling valve pressed (type:uint8_t)
-                venting_valve_btn         : Open venting valve pressed (type:uint8_t)
-                release_pressure_btn        : Release filling line pressure pressed (type:uint8_t)
-                quick_connector_btn        : Detach quick connector pressed (type:uint8_t)
-                start_tars_btn            : Startup TARS pressed (type:uint8_t)
-                arm_switch                : Arming switch state (type:uint8_t)
+        """
+        self.send(self.conrig_state_tc_encode(ignition_btn, filling_valve_btn, venting_valve_btn, release_pressure_btn, quick_connector_btn, start_tars_btn, arm_switch), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_conrig_state_tc_message(ignition_btn, filling_valve_btn, venting_valve_btn, release_pressure_btn, quick_connector_btn, start_tars_btn, arm_switch)
+    def set_ignition_time_tc_encode(self, timing: int) -> MAVLink_set_ignition_time_tc_message:
+        """
+        Sets the time in ms that the igniter stays on before the oxidant valve
+        is opened
 
-        def conrig_state_tc_send(self, ignition_btn, filling_valve_btn, venting_valve_btn, release_pressure_btn, quick_connector_btn, start_tars_btn, arm_switch, force_mavlink1=False):
-                '''
-                Send the state of the conrig buttons
+        timing                    : Timing in [ms] [ms] (type:uint32_t)
 
-                ignition_btn              : Ignition button pressed (type:uint8_t)
-                filling_valve_btn         : Open filling valve pressed (type:uint8_t)
-                venting_valve_btn         : Open venting valve pressed (type:uint8_t)
-                release_pressure_btn        : Release filling line pressure pressed (type:uint8_t)
-                quick_connector_btn        : Detach quick connector pressed (type:uint8_t)
-                start_tars_btn            : Startup TARS pressed (type:uint8_t)
-                arm_switch                : Arming switch state (type:uint8_t)
+        """
+        return MAVLink_set_ignition_time_tc_message(timing)
 
-                '''
-                return self.send(self.conrig_state_tc_encode(ignition_btn, filling_valve_btn, venting_valve_btn, release_pressure_btn, quick_connector_btn, start_tars_btn, arm_switch), force_mavlink1=force_mavlink1)
+    def set_ignition_time_tc_send(self, timing: int, force_mavlink1: bool = False) -> None:
+        """
+        Sets the time in ms that the igniter stays on before the oxidant valve
+        is opened
 
-        def set_ignition_time_tc_encode(self, timing):
-                '''
-                Sets the time in ms that the igniter stays on before the oxidant valve
-                is opened
+        timing                    : Timing in [ms] [ms] (type:uint32_t)
 
-                timing                    : Timing in [ms] [ms] (type:uint32_t)
+        """
+        self.send(self.set_ignition_time_tc_encode(timing), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_ignition_time_tc_message(timing)
+    def set_nitrogen_time_tc_encode(self, timing: int) -> MAVLink_set_nitrogen_time_tc_message:
+        """
+        Sets the time in ms that the nitrogen will stay open
 
-        def set_ignition_time_tc_send(self, timing, force_mavlink1=False):
-                '''
-                Sets the time in ms that the igniter stays on before the oxidant valve
-                is opened
+        timing                    : Timing in [ms] [ms] (type:uint32_t)
 
-                timing                    : Timing in [ms] [ms] (type:uint32_t)
+        """
+        return MAVLink_set_nitrogen_time_tc_message(timing)
 
-                '''
-                return self.send(self.set_ignition_time_tc_encode(timing), force_mavlink1=force_mavlink1)
+    def set_nitrogen_time_tc_send(self, timing: int, force_mavlink1: bool = False) -> None:
+        """
+        Sets the time in ms that the nitrogen will stay open
 
-        def set_nitrogen_time_tc_encode(self, timing):
-                '''
-                Sets the time in ms that the nitrogen will stay open
+        timing                    : Timing in [ms] [ms] (type:uint32_t)
 
-                timing                    : Timing in [ms] [ms] (type:uint32_t)
+        """
+        self.send(self.set_nitrogen_time_tc_encode(timing), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_nitrogen_time_tc_message(timing)
+    def set_cooling_time_tc_encode(self, timing: int) -> MAVLink_set_cooling_time_tc_message:
+        """
+        Sets the time in ms that the system will wait before disarming after
+        firing
 
-        def set_nitrogen_time_tc_send(self, timing, force_mavlink1=False):
-                '''
-                Sets the time in ms that the nitrogen will stay open
+        timing                    : Timing in [ms] [ms] (type:uint32_t)
 
-                timing                    : Timing in [ms] [ms] (type:uint32_t)
+        """
+        return MAVLink_set_cooling_time_tc_message(timing)
 
-                '''
-                return self.send(self.set_nitrogen_time_tc_encode(timing), force_mavlink1=force_mavlink1)
+    def set_cooling_time_tc_send(self, timing: int, force_mavlink1: bool = False) -> None:
+        """
+        Sets the time in ms that the system will wait before disarming after
+        firing
 
-        def set_cooling_time_tc_encode(self, timing):
-                '''
-                Sets the time in ms that the system will wait before disarming after
-                firing
+        timing                    : Timing in [ms] [ms] (type:uint32_t)
 
-                timing                    : Timing in [ms] [ms] (type:uint32_t)
+        """
+        self.send(self.set_cooling_time_tc_encode(timing), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_cooling_time_tc_message(timing)
+    def set_stepper_angle_tc_encode(self, stepper_id: int, angle: float) -> MAVLink_set_stepper_angle_tc_message:
+        """
+        Move the stepper of a certain angle
 
-        def set_cooling_time_tc_send(self, timing, force_mavlink1=False):
-                '''
-                Sets the time in ms that the system will wait before disarming after
-                firing
+        stepper_id                : A member of the StepperList enum (type:uint8_t)
+        angle                     : Stepper angle in degrees (type:float)
 
-                timing                    : Timing in [ms] [ms] (type:uint32_t)
+        """
+        return MAVLink_set_stepper_angle_tc_message(stepper_id, angle)
 
-                '''
-                return self.send(self.set_cooling_time_tc_encode(timing), force_mavlink1=force_mavlink1)
+    def set_stepper_angle_tc_send(self, stepper_id: int, angle: float, force_mavlink1: bool = False) -> None:
+        """
+        Move the stepper of a certain angle
 
-        def set_stepper_angle_tc_encode(self, stepper_id, angle):
-                '''
-                Move the stepper of a certain angle
+        stepper_id                : A member of the StepperList enum (type:uint8_t)
+        angle                     : Stepper angle in degrees (type:float)
 
-                stepper_id                : A member of the StepperList enum (type:uint8_t)
-                angle                     : Stepper angle in degrees (type:float)
+        """
+        self.send(self.set_stepper_angle_tc_encode(stepper_id, angle), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_set_stepper_angle_tc_message(stepper_id, angle)
+    def set_stepper_steps_tc_encode(self, stepper_id: int, steps: float) -> MAVLink_set_stepper_steps_tc_message:
+        """
+        Move the stepper of a certain amount of steps
 
-        def set_stepper_angle_tc_send(self, stepper_id, angle, force_mavlink1=False):
-                '''
-                Move the stepper of a certain angle
+        stepper_id                : A member of the StepperList enum (type:uint8_t)
+        steps                     : Number of steps (type:float)
 
-                stepper_id                : A member of the StepperList enum (type:uint8_t)
-                angle                     : Stepper angle in degrees (type:float)
+        """
+        return MAVLink_set_stepper_steps_tc_message(stepper_id, steps)
 
-                '''
-                return self.send(self.set_stepper_angle_tc_encode(stepper_id, angle), force_mavlink1=force_mavlink1)
+    def set_stepper_steps_tc_send(self, stepper_id: int, steps: float, force_mavlink1: bool = False) -> None:
+        """
+        Move the stepper of a certain amount of steps
 
-        def set_stepper_steps_tc_encode(self, stepper_id, steps):
-                '''
-                Move the stepper of a certain amount of steps
+        stepper_id                : A member of the StepperList enum (type:uint8_t)
+        steps                     : Number of steps (type:float)
+
+        """
+        self.send(self.set_stepper_steps_tc_encode(stepper_id, steps), force_mavlink1=force_mavlink1)
+
+    def ack_tm_encode(self, recv_msgid: int, seq_ack: int) -> MAVLink_ack_tm_message:
+        """
+        TM containing an ACK message to notify that the message has been
+        processed correctly
+
+        recv_msgid                : Message id of the received message (type:uint8_t)
+        seq_ack                   : Sequence number of the received message (type:uint8_t)
+
+        """
+        return MAVLink_ack_tm_message(recv_msgid, seq_ack)
+
+    def ack_tm_send(self, recv_msgid: int, seq_ack: int, force_mavlink1: bool = False) -> None:
+        """
+        TM containing an ACK message to notify that the message has been
+        processed correctly
+
+        recv_msgid                : Message id of the received message (type:uint8_t)
+        seq_ack                   : Sequence number of the received message (type:uint8_t)
+
+        """
+        self.send(self.ack_tm_encode(recv_msgid, seq_ack), force_mavlink1=force_mavlink1)
+
+    def nack_tm_encode(self, recv_msgid: int, seq_ack: int, err_id: int) -> MAVLink_nack_tm_message:
+        """
+        TM containing a NACK message to notify that the received message was
+        invalid
+
+        recv_msgid                : Message id of the received message (type:uint8_t)
+        seq_ack                   : Sequence number of the received message (type:uint8_t)
+        err_id                    : Error core that generated the NACK (type:uint16_t)
+
+        """
+        return MAVLink_nack_tm_message(recv_msgid, seq_ack, err_id)
+
+    def nack_tm_send(self, recv_msgid: int, seq_ack: int, err_id: int, force_mavlink1: bool = False) -> None:
+        """
+        TM containing a NACK message to notify that the received message was
+        invalid
+
+        recv_msgid                : Message id of the received message (type:uint8_t)
+        seq_ack                   : Sequence number of the received message (type:uint8_t)
+        err_id                    : Error core that generated the NACK (type:uint16_t)
+
+        """
+        self.send(self.nack_tm_encode(recv_msgid, seq_ack, err_id), force_mavlink1=force_mavlink1)
+
+    def wack_tm_encode(self, recv_msgid: int, seq_ack: int, err_id: int) -> MAVLink_wack_tm_message:
+        """
+        TM containing an ACK message to notify that the message has been
+        processed with a warning
+
+        recv_msgid                : Message id of the received message (type:uint8_t)
+        seq_ack                   : Sequence number of the received message (type:uint8_t)
+        err_id                    : Error core that generated the WACK (type:uint16_t)
+
+        """
+        return MAVLink_wack_tm_message(recv_msgid, seq_ack, err_id)
+
+    def wack_tm_send(self, recv_msgid: int, seq_ack: int, err_id: int, force_mavlink1: bool = False) -> None:
+        """
+        TM containing an ACK message to notify that the message has been
+        processed with a warning
+
+        recv_msgid                : Message id of the received message (type:uint8_t)
+        seq_ack                   : Sequence number of the received message (type:uint8_t)
+        err_id                    : Error core that generated the WACK (type:uint16_t)
+
+        """
+        self.send(self.wack_tm_encode(recv_msgid, seq_ack, err_id), force_mavlink1=force_mavlink1)
+
+    def gps_tm_encode(self, timestamp: int, sensor_name: bytes, fix: int, latitude: float, longitude: float, height: float, vel_north: float, vel_east: float, vel_down: float, speed: float, track: float, n_satellites: int) -> MAVLink_gps_tm_message:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        fix                       : Wether the GPS has a FIX (type:uint8_t)
+        latitude                  : Latitude [deg] (type:double)
+        longitude                 : Longitude [deg] (type:double)
+        height                    : Altitude [m] (type:double)
+        vel_north                 : Velocity in NED frame (north) [m/s] (type:float)
+        vel_east                  : Velocity in NED frame (east) [m/s] (type:float)
+        vel_down                  : Velocity in NED frame (down) [m/s] (type:float)
+        speed                     : Speed [m/s] (type:float)
+        track                     : Track [deg] (type:float)
+        n_satellites              : Number of connected satellites (type:uint8_t)
+
+        """
+        return MAVLink_gps_tm_message(timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites)
+
+    def gps_tm_send(self, timestamp: int, sensor_name: bytes, fix: int, latitude: float, longitude: float, height: float, vel_north: float, vel_east: float, vel_down: float, speed: float, track: float, n_satellites: int, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        fix                       : Wether the GPS has a FIX (type:uint8_t)
+        latitude                  : Latitude [deg] (type:double)
+        longitude                 : Longitude [deg] (type:double)
+        height                    : Altitude [m] (type:double)
+        vel_north                 : Velocity in NED frame (north) [m/s] (type:float)
+        vel_east                  : Velocity in NED frame (east) [m/s] (type:float)
+        vel_down                  : Velocity in NED frame (down) [m/s] (type:float)
+        speed                     : Speed [m/s] (type:float)
+        track                     : Track [deg] (type:float)
+        n_satellites              : Number of connected satellites (type:uint8_t)
+
+        """
+        self.send(self.gps_tm_encode(timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites), force_mavlink1=force_mavlink1)
+
+    def imu_tm_encode(self, timestamp: int, sensor_name: bytes, acc_x: float, acc_y: float, acc_z: float, gyro_x: float, gyro_y: float, gyro_z: float, mag_x: float, mag_y: float, mag_z: float) -> MAVLink_imu_tm_message:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        acc_x                     : X axis acceleration [m/s2] (type:float)
+        acc_y                     : Y axis acceleration [m/s2] (type:float)
+        acc_z                     : Z axis acceleration [m/s2] (type:float)
+        gyro_x                    : X axis gyro [rad/s] (type:float)
+        gyro_y                    : Y axis gyro [rad/s] (type:float)
+        gyro_z                    : Z axis gyro [rad/s] (type:float)
+        mag_x                     : X axis compass [uT] (type:float)
+        mag_y                     : Y axis compass [uT] (type:float)
+        mag_z                     : Z axis compass [uT] (type:float)
+
+        """
+        return MAVLink_imu_tm_message(timestamp, sensor_name, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z)
+
+    def imu_tm_send(self, timestamp: int, sensor_name: bytes, acc_x: float, acc_y: float, acc_z: float, gyro_x: float, gyro_y: float, gyro_z: float, mag_x: float, mag_y: float, mag_z: float, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        acc_x                     : X axis acceleration [m/s2] (type:float)
+        acc_y                     : Y axis acceleration [m/s2] (type:float)
+        acc_z                     : Z axis acceleration [m/s2] (type:float)
+        gyro_x                    : X axis gyro [rad/s] (type:float)
+        gyro_y                    : Y axis gyro [rad/s] (type:float)
+        gyro_z                    : Z axis gyro [rad/s] (type:float)
+        mag_x                     : X axis compass [uT] (type:float)
+        mag_y                     : Y axis compass [uT] (type:float)
+        mag_z                     : Z axis compass [uT] (type:float)
+
+        """
+        self.send(self.imu_tm_encode(timestamp, sensor_name, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z), force_mavlink1=force_mavlink1)
+
+    def pressure_tm_encode(self, timestamp: int, sensor_name: bytes, pressure: float) -> MAVLink_pressure_tm_message:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        pressure                  : Pressure of the digital barometer [Pa] (type:float)
+
+        """
+        return MAVLink_pressure_tm_message(timestamp, sensor_name, pressure)
+
+    def pressure_tm_send(self, timestamp: int, sensor_name: bytes, pressure: float, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        pressure                  : Pressure of the digital barometer [Pa] (type:float)
+
+        """
+        self.send(self.pressure_tm_encode(timestamp, sensor_name, pressure), force_mavlink1=force_mavlink1)
+
+    def adc_tm_encode(self, timestamp: int, sensor_name: bytes, channel_0: float, channel_1: float, channel_2: float, channel_3: float, channel_4: float, channel_5: float, channel_6: float, channel_7: float) -> MAVLink_adc_tm_message:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        channel_0                 : ADC voltage measured on channel 0 [V] (type:float)
+        channel_1                 : ADC voltage measured on channel 1 [V] (type:float)
+        channel_2                 : ADC voltage measured on channel 2 [V] (type:float)
+        channel_3                 : ADC voltage measured on channel 3 [V] (type:float)
+        channel_4                 : ADC voltage measured on channel 4 [V] (type:float)
+        channel_5                 : ADC voltage measured on channel 5 [V] (type:float)
+        channel_6                 : ADC voltage measured on channel 6 [V] (type:float)
+        channel_7                 : ADC voltage measured on channel 7 [V] (type:float)
+
+        """
+        return MAVLink_adc_tm_message(timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7)
+
+    def adc_tm_send(self, timestamp: int, sensor_name: bytes, channel_0: float, channel_1: float, channel_2: float, channel_3: float, channel_4: float, channel_5: float, channel_6: float, channel_7: float, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        channel_0                 : ADC voltage measured on channel 0 [V] (type:float)
+        channel_1                 : ADC voltage measured on channel 1 [V] (type:float)
+        channel_2                 : ADC voltage measured on channel 2 [V] (type:float)
+        channel_3                 : ADC voltage measured on channel 3 [V] (type:float)
+        channel_4                 : ADC voltage measured on channel 4 [V] (type:float)
+        channel_5                 : ADC voltage measured on channel 5 [V] (type:float)
+        channel_6                 : ADC voltage measured on channel 6 [V] (type:float)
+        channel_7                 : ADC voltage measured on channel 7 [V] (type:float)
+
+        """
+        self.send(self.adc_tm_encode(timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7), force_mavlink1=force_mavlink1)
+
+    def voltage_tm_encode(self, timestamp: int, sensor_name: bytes, voltage: float) -> MAVLink_voltage_tm_message:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        voltage                   : Voltage [V] (type:float)
+
+        """
+        return MAVLink_voltage_tm_message(timestamp, sensor_name, voltage)
+
+    def voltage_tm_send(self, timestamp: int, sensor_name: bytes, voltage: float, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        voltage                   : Voltage [V] (type:float)
+
+        """
+        self.send(self.voltage_tm_encode(timestamp, sensor_name, voltage), force_mavlink1=force_mavlink1)
+
+    def current_tm_encode(self, timestamp: int, sensor_name: bytes, current: float) -> MAVLink_current_tm_message:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        current                   : Current [A] (type:float)
+
+        """
+        return MAVLink_current_tm_message(timestamp, sensor_name, current)
+
+    def current_tm_send(self, timestamp: int, sensor_name: bytes, current: float, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        current                   : Current [A] (type:float)
+
+        """
+        self.send(self.current_tm_encode(timestamp, sensor_name, current), force_mavlink1=force_mavlink1)
+
+    def temp_tm_encode(self, timestamp: int, sensor_name: bytes, temperature: float) -> MAVLink_temp_tm_message:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        temperature               : Temperature [deg] (type:float)
+
+        """
+        return MAVLink_temp_tm_message(timestamp, sensor_name, temperature)
+
+    def temp_tm_send(self, timestamp: int, sensor_name: bytes, temperature: float, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        temperature               : Temperature [deg] (type:float)
+
+        """
+        self.send(self.temp_tm_encode(timestamp, sensor_name, temperature), force_mavlink1=force_mavlink1)
+
+    def load_tm_encode(self, timestamp: int, sensor_name: bytes, load: float) -> MAVLink_load_tm_message:
+        """
+        
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        load                      : Load force [kg] (type:float)
+
+        """
+        return MAVLink_load_tm_message(timestamp, sensor_name, load)
 
-                stepper_id                : A member of the StepperList enum (type:uint8_t)
-                steps                     : Number of steps (type:float)
+    def load_tm_send(self, timestamp: int, sensor_name: bytes, load: float, force_mavlink1: bool = False) -> None:
+        """
+        
 
-                '''
-                return MAVLink_set_stepper_steps_tc_message(stepper_id, steps)
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        load                      : Load force [kg] (type:float)
+
+        """
+        self.send(self.load_tm_encode(timestamp, sensor_name, load), force_mavlink1=force_mavlink1)
+
+    def attitude_tm_encode(self, timestamp: int, sensor_name: bytes, roll: float, pitch: float, yaw: float, quat_x: float, quat_y: float, quat_z: float, quat_w: float) -> MAVLink_attitude_tm_message:
+        """
+        
 
-        def set_stepper_steps_tc_send(self, stepper_id, steps, force_mavlink1=False):
-                '''
-                Move the stepper of a certain amount of steps
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        roll                      : Roll angle [deg] (type:float)
+        pitch                     : Pitch angle [deg] (type:float)
+        yaw                       : Yaw angle [deg] (type:float)
+        quat_x                    : Quaternion x component (type:float)
+        quat_y                    : Quaternion y component (type:float)
+        quat_z                    : Quaternion z component (type:float)
+        quat_w                    : Quaternion w component (type:float)
 
-                stepper_id                : A member of the StepperList enum (type:uint8_t)
-                steps                     : Number of steps (type:float)
+        """
+        return MAVLink_attitude_tm_message(timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w)
 
-                '''
-                return self.send(self.set_stepper_steps_tc_encode(stepper_id, steps), force_mavlink1=force_mavlink1)
+    def attitude_tm_send(self, timestamp: int, sensor_name: bytes, roll: float, pitch: float, yaw: float, quat_x: float, quat_y: float, quat_z: float, quat_w: float, force_mavlink1: bool = False) -> None:
+        """
+        
 
-        def ack_tm_encode(self, recv_msgid, seq_ack):
-                '''
-                TM containing an ACK message to notify that the message has been
-                processed correctly
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        sensor_name               : Sensor name (type:char)
+        roll                      : Roll angle [deg] (type:float)
+        pitch                     : Pitch angle [deg] (type:float)
+        yaw                       : Yaw angle [deg] (type:float)
+        quat_x                    : Quaternion x component (type:float)
+        quat_y                    : Quaternion y component (type:float)
+        quat_z                    : Quaternion z component (type:float)
+        quat_w                    : Quaternion w component (type:float)
 
-                recv_msgid                : Message id of the received message (type:uint8_t)
-                seq_ack                   : Sequence number of the received message (type:uint8_t)
+        """
+        self.send(self.attitude_tm_encode(timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_ack_tm_message(recv_msgid, seq_ack)
+    def sensor_state_tm_encode(self, sensor_name: bytes, initialized: int, enabled: int) -> MAVLink_sensor_state_tm_message:
+        """
+        
 
-        def ack_tm_send(self, recv_msgid, seq_ack, force_mavlink1=False):
-                '''
-                TM containing an ACK message to notify that the message has been
-                processed correctly
+        sensor_name               : Sensor name (type:char)
+        initialized               : Boolean that represents the init state (type:uint8_t)
+        enabled                   : Boolean that represents the enabled state (type:uint8_t)
 
-                recv_msgid                : Message id of the received message (type:uint8_t)
-                seq_ack                   : Sequence number of the received message (type:uint8_t)
+        """
+        return MAVLink_sensor_state_tm_message(sensor_name, initialized, enabled)
 
-                '''
-                return self.send(self.ack_tm_encode(recv_msgid, seq_ack), force_mavlink1=force_mavlink1)
+    def sensor_state_tm_send(self, sensor_name: bytes, initialized: int, enabled: int, force_mavlink1: bool = False) -> None:
+        """
+        
 
-        def nack_tm_encode(self, recv_msgid, seq_ack, err_id):
-                '''
-                TM containing a NACK message to notify that the received message was
-                invalid
-
-                recv_msgid                : Message id of the received message (type:uint8_t)
-                seq_ack                   : Sequence number of the received message (type:uint8_t)
-                err_id                    : Error core that generated the NACK (type:uint16_t)
-
-                '''
-                return MAVLink_nack_tm_message(recv_msgid, seq_ack, err_id)
-
-        def nack_tm_send(self, recv_msgid, seq_ack, err_id, force_mavlink1=False):
-                '''
-                TM containing a NACK message to notify that the received message was
-                invalid
-
-                recv_msgid                : Message id of the received message (type:uint8_t)
-                seq_ack                   : Sequence number of the received message (type:uint8_t)
-                err_id                    : Error core that generated the NACK (type:uint16_t)
-
-                '''
-                return self.send(self.nack_tm_encode(recv_msgid, seq_ack, err_id), force_mavlink1=force_mavlink1)
-
-        def wack_tm_encode(self, recv_msgid, seq_ack, err_id):
-                '''
-                TM containing an ACK message to notify that the message has been
-                processed with a warning
-
-                recv_msgid                : Message id of the received message (type:uint8_t)
-                seq_ack                   : Sequence number of the received message (type:uint8_t)
-                err_id                    : Error core that generated the WACK (type:uint16_t)
-
-                '''
-                return MAVLink_wack_tm_message(recv_msgid, seq_ack, err_id)
-
-        def wack_tm_send(self, recv_msgid, seq_ack, err_id, force_mavlink1=False):
-                '''
-                TM containing an ACK message to notify that the message has been
-                processed with a warning
-
-                recv_msgid                : Message id of the received message (type:uint8_t)
-                seq_ack                   : Sequence number of the received message (type:uint8_t)
-                err_id                    : Error core that generated the WACK (type:uint16_t)
-
-                '''
-                return self.send(self.wack_tm_encode(recv_msgid, seq_ack, err_id), force_mavlink1=force_mavlink1)
-
-        def gps_tm_encode(self, timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                fix                       : Wether the GPS has a FIX (type:uint8_t)
-                latitude                  : Latitude [deg] (type:double)
-                longitude                 : Longitude [deg] (type:double)
-                height                    : Altitude [m] (type:double)
-                vel_north                 : Velocity in NED frame (north) [m/s] (type:float)
-                vel_east                  : Velocity in NED frame (east) [m/s] (type:float)
-                vel_down                  : Velocity in NED frame (down) [m/s] (type:float)
-                speed                     : Speed [m/s] (type:float)
-                track                     : Track [deg] (type:float)
-                n_satellites              : Number of connected satellites (type:uint8_t)
-
-                '''
-                return MAVLink_gps_tm_message(timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites)
-
-        def gps_tm_send(self, timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                fix                       : Wether the GPS has a FIX (type:uint8_t)
-                latitude                  : Latitude [deg] (type:double)
-                longitude                 : Longitude [deg] (type:double)
-                height                    : Altitude [m] (type:double)
-                vel_north                 : Velocity in NED frame (north) [m/s] (type:float)
-                vel_east                  : Velocity in NED frame (east) [m/s] (type:float)
-                vel_down                  : Velocity in NED frame (down) [m/s] (type:float)
-                speed                     : Speed [m/s] (type:float)
-                track                     : Track [deg] (type:float)
-                n_satellites              : Number of connected satellites (type:uint8_t)
-
-                '''
-                return self.send(self.gps_tm_encode(timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites), force_mavlink1=force_mavlink1)
-
-        def imu_tm_encode(self, timestamp, sensor_name, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                acc_x                     : X axis acceleration [m/s2] (type:float)
-                acc_y                     : Y axis acceleration [m/s2] (type:float)
-                acc_z                     : Z axis acceleration [m/s2] (type:float)
-                gyro_x                    : X axis gyro [rad/s] (type:float)
-                gyro_y                    : Y axis gyro [rad/s] (type:float)
-                gyro_z                    : Z axis gyro [rad/s] (type:float)
-                mag_x                     : X axis compass [uT] (type:float)
-                mag_y                     : Y axis compass [uT] (type:float)
-                mag_z                     : Z axis compass [uT] (type:float)
-
-                '''
-                return MAVLink_imu_tm_message(timestamp, sensor_name, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z)
-
-        def imu_tm_send(self, timestamp, sensor_name, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                acc_x                     : X axis acceleration [m/s2] (type:float)
-                acc_y                     : Y axis acceleration [m/s2] (type:float)
-                acc_z                     : Z axis acceleration [m/s2] (type:float)
-                gyro_x                    : X axis gyro [rad/s] (type:float)
-                gyro_y                    : Y axis gyro [rad/s] (type:float)
-                gyro_z                    : Z axis gyro [rad/s] (type:float)
-                mag_x                     : X axis compass [uT] (type:float)
-                mag_y                     : Y axis compass [uT] (type:float)
-                mag_z                     : Z axis compass [uT] (type:float)
-
-                '''
-                return self.send(self.imu_tm_encode(timestamp, sensor_name, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z), force_mavlink1=force_mavlink1)
-
-        def pressure_tm_encode(self, timestamp, sensor_name, pressure):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                pressure                  : Pressure of the digital barometer [Pa] (type:float)
-
-                '''
-                return MAVLink_pressure_tm_message(timestamp, sensor_name, pressure)
-
-        def pressure_tm_send(self, timestamp, sensor_name, pressure, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                pressure                  : Pressure of the digital barometer [Pa] (type:float)
-
-                '''
-                return self.send(self.pressure_tm_encode(timestamp, sensor_name, pressure), force_mavlink1=force_mavlink1)
-
-        def adc_tm_encode(self, timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                channel_0                 : ADC voltage measured on channel 0 [V] (type:float)
-                channel_1                 : ADC voltage measured on channel 1 [V] (type:float)
-                channel_2                 : ADC voltage measured on channel 2 [V] (type:float)
-                channel_3                 : ADC voltage measured on channel 3 [V] (type:float)
-                channel_4                 : ADC voltage measured on channel 4 [V] (type:float)
-                channel_5                 : ADC voltage measured on channel 5 [V] (type:float)
-                channel_6                 : ADC voltage measured on channel 6 [V] (type:float)
-                channel_7                 : ADC voltage measured on channel 7 [V] (type:float)
-
-                '''
-                return MAVLink_adc_tm_message(timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7)
-
-        def adc_tm_send(self, timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                channel_0                 : ADC voltage measured on channel 0 [V] (type:float)
-                channel_1                 : ADC voltage measured on channel 1 [V] (type:float)
-                channel_2                 : ADC voltage measured on channel 2 [V] (type:float)
-                channel_3                 : ADC voltage measured on channel 3 [V] (type:float)
-                channel_4                 : ADC voltage measured on channel 4 [V] (type:float)
-                channel_5                 : ADC voltage measured on channel 5 [V] (type:float)
-                channel_6                 : ADC voltage measured on channel 6 [V] (type:float)
-                channel_7                 : ADC voltage measured on channel 7 [V] (type:float)
-
-                '''
-                return self.send(self.adc_tm_encode(timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7), force_mavlink1=force_mavlink1)
-
-        def voltage_tm_encode(self, timestamp, sensor_name, voltage):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                voltage                   : Voltage [V] (type:float)
-
-                '''
-                return MAVLink_voltage_tm_message(timestamp, sensor_name, voltage)
-
-        def voltage_tm_send(self, timestamp, sensor_name, voltage, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                voltage                   : Voltage [V] (type:float)
-
-                '''
-                return self.send(self.voltage_tm_encode(timestamp, sensor_name, voltage), force_mavlink1=force_mavlink1)
-
-        def current_tm_encode(self, timestamp, sensor_name, current):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                current                   : Current [A] (type:float)
-
-                '''
-                return MAVLink_current_tm_message(timestamp, sensor_name, current)
-
-        def current_tm_send(self, timestamp, sensor_name, current, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                current                   : Current [A] (type:float)
-
-                '''
-                return self.send(self.current_tm_encode(timestamp, sensor_name, current), force_mavlink1=force_mavlink1)
-
-        def temp_tm_encode(self, timestamp, sensor_name, temperature):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                temperature               : Temperature [deg] (type:float)
-
-                '''
-                return MAVLink_temp_tm_message(timestamp, sensor_name, temperature)
-
-        def temp_tm_send(self, timestamp, sensor_name, temperature, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                temperature               : Temperature [deg] (type:float)
-
-                '''
-                return self.send(self.temp_tm_encode(timestamp, sensor_name, temperature), force_mavlink1=force_mavlink1)
-
-        def load_tm_encode(self, timestamp, sensor_name, load):
-                '''
-                
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                load                      : Load force [kg] (type:float)
-
-                '''
-                return MAVLink_load_tm_message(timestamp, sensor_name, load)
+        sensor_name               : Sensor name (type:char)
+        initialized               : Boolean that represents the init state (type:uint8_t)
+        enabled                   : Boolean that represents the enabled state (type:uint8_t)
 
-        def load_tm_send(self, timestamp, sensor_name, load, force_mavlink1=False):
-                '''
-                
+        """
+        self.send(self.sensor_state_tm_encode(sensor_name, initialized, enabled), force_mavlink1=force_mavlink1)
 
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                load                      : Load force [kg] (type:float)
-
-                '''
-                return self.send(self.load_tm_encode(timestamp, sensor_name, load), force_mavlink1=force_mavlink1)
-
-        def attitude_tm_encode(self, timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w):
-                '''
-                
+    def servo_tm_encode(self, servo_id: int, servo_position: float) -> MAVLink_servo_tm_message:
+        """
+        
 
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                roll                      : Roll angle [deg] (type:float)
-                pitch                     : Pitch angle [deg] (type:float)
-                yaw                       : Yaw angle [deg] (type:float)
-                quat_x                    : Quaternion x component (type:float)
-                quat_y                    : Quaternion y component (type:float)
-                quat_z                    : Quaternion z component (type:float)
-                quat_w                    : Quaternion w component (type:float)
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
+        servo_position            : Position of the servo [0-1] (type:float)
 
-                '''
-                return MAVLink_attitude_tm_message(timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w)
+        """
+        return MAVLink_servo_tm_message(servo_id, servo_position)
+
+    def servo_tm_send(self, servo_id: int, servo_position: float, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        servo_id                  : A member of the ServosList enum (type:uint8_t)
+        servo_position            : Position of the servo [0-1] (type:float)
+
+        """
+        self.send(self.servo_tm_encode(servo_id, servo_position), force_mavlink1=force_mavlink1)
+
+    def pin_tm_encode(self, timestamp: int, pin_id: int, last_change_timestamp: int, changes_counter: int, current_state: int) -> MAVLink_pin_tm_message:
+        """
+        
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        pin_id                    : A member of the PinsList enum (type:uint8_t)
+        last_change_timestamp        : Last change timestamp of pin (type:uint64_t)
+        changes_counter           : Number of changes of pin (type:uint8_t)
+        current_state             : Current state of pin (type:uint8_t)
+
+        """
+        return MAVLink_pin_tm_message(timestamp, pin_id, last_change_timestamp, changes_counter, current_state)
+
+    def pin_tm_send(self, timestamp: int, pin_id: int, last_change_timestamp: int, changes_counter: int, current_state: int, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        pin_id                    : A member of the PinsList enum (type:uint8_t)
+        last_change_timestamp        : Last change timestamp of pin (type:uint64_t)
+        changes_counter           : Number of changes of pin (type:uint8_t)
+        current_state             : Current state of pin (type:uint8_t)
+
+        """
+        self.send(self.pin_tm_encode(timestamp, pin_id, last_change_timestamp, changes_counter, current_state), force_mavlink1=force_mavlink1)
+
+    def registry_float_tm_encode(self, timestamp: int, key_id: int, key_name: bytes, value: float) -> MAVLink_registry_float_tm_message:
+        """
+        
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        key_id                    : Id of this configuration entry (type:uint32_t)
+        key_name                  : Name of this configuration entry (type:char)
+        value                     : Value of this configuration (type:float)
+
+        """
+        return MAVLink_registry_float_tm_message(timestamp, key_id, key_name, value)
+
+    def registry_float_tm_send(self, timestamp: int, key_id: int, key_name: bytes, value: float, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        key_id                    : Id of this configuration entry (type:uint32_t)
+        key_name                  : Name of this configuration entry (type:char)
+        value                     : Value of this configuration (type:float)
+
+        """
+        self.send(self.registry_float_tm_encode(timestamp, key_id, key_name, value), force_mavlink1=force_mavlink1)
+
+    def registry_int_tm_encode(self, timestamp: int, key_id: int, key_name: bytes, value: int) -> MAVLink_registry_int_tm_message:
+        """
+        
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        key_id                    : Id of this configuration entry (type:uint32_t)
+        key_name                  : Name of this configuration entry (type:char)
+        value                     : Value of this configuration (type:uint32_t)
+
+        """
+        return MAVLink_registry_int_tm_message(timestamp, key_id, key_name, value)
+
+    def registry_int_tm_send(self, timestamp: int, key_id: int, key_name: bytes, value: int, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        key_id                    : Id of this configuration entry (type:uint32_t)
+        key_name                  : Name of this configuration entry (type:char)
+        value                     : Value of this configuration (type:uint32_t)
+
+        """
+        self.send(self.registry_int_tm_encode(timestamp, key_id, key_name, value), force_mavlink1=force_mavlink1)
+
+    def registry_coord_tm_encode(self, timestamp: int, key_id: int, key_name: bytes, latitude: float, longitude: float) -> MAVLink_registry_coord_tm_message:
+        """
+        
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        key_id                    : Id of this configuration entry (type:uint32_t)
+        key_name                  : Name of this configuration entry (type:char)
+        latitude                  : Latitude in this configuration [deg] (type:float)
+        longitude                 : Latitude in this configuration [deg] (type:float)
+
+        """
+        return MAVLink_registry_coord_tm_message(timestamp, key_id, key_name, latitude, longitude)
+
+    def registry_coord_tm_send(self, timestamp: int, key_id: int, key_name: bytes, latitude: float, longitude: float, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        key_id                    : Id of this configuration entry (type:uint32_t)
+        key_name                  : Name of this configuration entry (type:char)
+        latitude                  : Latitude in this configuration [deg] (type:float)
+        longitude                 : Latitude in this configuration [deg] (type:float)
+
+        """
+        self.send(self.registry_coord_tm_encode(timestamp, key_id, key_name, latitude, longitude), force_mavlink1=force_mavlink1)
+
+    def arp_tm_encode(self, timestamp: int, state: int, 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: float, gps_fix: int, main_radio_present: int, main_packet_tx_error_count: int, main_tx_bitrate: int, main_packet_rx_success_count: int, main_packet_rx_drop_count: int, main_rx_bitrate: int, main_rx_rssi: float, payload_radio_present: int, payload_packet_tx_error_count: int, payload_tx_bitrate: int, payload_packet_rx_success_count: int, payload_packet_rx_drop_count: int, payload_rx_bitrate: int, payload_rx_rssi: float, ethernet_present: int, ethernet_status: int, battery_voltage: float, log_number: int) -> MAVLink_arp_tm_message:
+        """
+        
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        state                     : State Machine Controller State (type:uint8_t)
+        yaw                       : Current Yaw [deg] (type:float)
+        pitch                     : Current Pitch [deg] (type:float)
+        roll                      : Current Roll [deg] (type:float)
+        target_yaw                : Target Yaw [deg] (type:float)
+        target_pitch              : Target Pitch [deg] (type:float)
+        stepperX_pos              : StepperX current position wrt the boot position [deg] (type:float)
+        stepperX_delta            : StepperX last actuated delta angle [deg] (type:float)
+        stepperX_speed            : StepperX current speed [rps] (type:float)
+        stepperY_pos              : StepperY current position wrt the boot position [deg] (type:float)
+        stepperY_delta            : StepperY last actuated delta angle [deg] (type:float)
+        stepperY_speed            : StepperY current Speed [rps] (type:float)
+        gps_latitude              : Latitude [deg] (type:float)
+        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)
+
+    def arp_tm_send(self, timestamp: int, state: int, 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: float, gps_fix: int, main_radio_present: int, main_packet_tx_error_count: int, main_tx_bitrate: int, main_packet_rx_success_count: int, main_packet_rx_drop_count: int, main_rx_bitrate: int, main_rx_rssi: float, payload_radio_present: int, payload_packet_tx_error_count: int, payload_tx_bitrate: int, payload_packet_rx_success_count: int, payload_packet_rx_drop_count: int, payload_rx_bitrate: int, payload_rx_rssi: float, ethernet_present: int, ethernet_status: int, battery_voltage: float, log_number: int, force_mavlink1: bool = False) -> None:
+        """
+        
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        state                     : State Machine Controller State (type:uint8_t)
+        yaw                       : Current Yaw [deg] (type:float)
+        pitch                     : Current Pitch [deg] (type:float)
+        roll                      : Current Roll [deg] (type:float)
+        target_yaw                : Target Yaw [deg] (type:float)
+        target_pitch              : Target Pitch [deg] (type:float)
+        stepperX_pos              : StepperX current position wrt the boot position [deg] (type:float)
+        stepperX_delta            : StepperX last actuated delta angle [deg] (type:float)
+        stepperX_speed            : StepperX current speed [rps] (type:float)
+        stepperY_pos              : StepperY current position wrt the boot position [deg] (type:float)
+        stepperY_delta            : StepperY last actuated delta angle [deg] (type:float)
+        stepperY_speed            : StepperY current Speed [rps] (type:float)
+        gps_latitude              : Latitude [deg] (type:float)
+        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)
+
+        """
+        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)
+
+    def set_antenna_coordinates_arp_tc_encode(self, latitude: float, longitude: float, height: float) -> MAVLink_set_antenna_coordinates_arp_tc_message:
+        """
+        Sets current antennas coordinates
 
-        def attitude_tm_send(self, timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w, force_mavlink1=False):
-                '''
-                
+        latitude                  : Latitude [deg] (type:float)
+        longitude                 : Longitude [deg] (type:float)
+        height                    : Height [m] (type:float)
 
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                sensor_name               : Sensor name (type:char)
-                roll                      : Roll angle [deg] (type:float)
-                pitch                     : Pitch angle [deg] (type:float)
-                yaw                       : Yaw angle [deg] (type:float)
-                quat_x                    : Quaternion x component (type:float)
-                quat_y                    : Quaternion y component (type:float)
-                quat_z                    : Quaternion z component (type:float)
-                quat_w                    : Quaternion w component (type:float)
+        """
+        return MAVLink_set_antenna_coordinates_arp_tc_message(latitude, longitude, height)
 
-                '''
-                return self.send(self.attitude_tm_encode(timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w), force_mavlink1=force_mavlink1)
+    def set_antenna_coordinates_arp_tc_send(self, latitude: float, longitude: float, height: float, force_mavlink1: bool = False) -> None:
+        """
+        Sets current antennas coordinates
 
-        def sensor_state_tm_encode(self, sensor_name, initialized, enabled):
-                '''
-                
+        latitude                  : Latitude [deg] (type:float)
+        longitude                 : Longitude [deg] (type:float)
+        height                    : Height [m] (type:float)
 
-                sensor_name               : Sensor name (type:char)
-                initialized               : Boolean that represents the init state (type:uint8_t)
-                enabled                   : Boolean that represents the enabled state (type:uint8_t)
+        """
+        self.send(self.set_antenna_coordinates_arp_tc_encode(latitude, longitude, height), force_mavlink1=force_mavlink1)
 
-                '''
-                return MAVLink_sensor_state_tm_message(sensor_name, initialized, enabled)
+    def set_rocket_coordinates_arp_tc_encode(self, latitude: float, longitude: float, height: float) -> MAVLink_set_rocket_coordinates_arp_tc_message:
+        """
+        Sets current rocket coordinates
+
+        latitude                  : Latitude [deg] (type:float)
+        longitude                 : Longitude [deg] (type:float)
+        height                    : Height [m] (type:float)
+
+        """
+        return MAVLink_set_rocket_coordinates_arp_tc_message(latitude, longitude, height)
+
+    def set_rocket_coordinates_arp_tc_send(self, latitude: float, longitude: float, height: float, force_mavlink1: bool = False) -> None:
+        """
+        Sets current rocket coordinates
+
+        latitude                  : Latitude [deg] (type:float)
+        longitude                 : Longitude [deg] (type:float)
+        height                    : Height [m] (type:float)
+
+        """
+        self.send(self.set_rocket_coordinates_arp_tc_encode(latitude, longitude, height), force_mavlink1=force_mavlink1)
+
+    def arp_command_tc_encode(self, command_id: int) -> MAVLink_arp_command_tc_message:
+        """
+        TC containing a command with no parameters that trigger some action
+
+        command_id                : A member of the MavArpCommandList enum (type:uint8_t)
+
+        """
+        return MAVLink_arp_command_tc_message(command_id)
+
+    def arp_command_tc_send(self, command_id: int, force_mavlink1: bool = False) -> None:
+        """
+        TC containing a command with no parameters that trigger some action
+
+        command_id                : A member of the MavArpCommandList enum (type:uint8_t)
+
+        """
+        self.send(self.arp_command_tc_encode(command_id), force_mavlink1=force_mavlink1)
+
+    def sys_tm_encode(self, timestamp: int, logger: int, event_broker: int, radio: int, sensors: int, actuators: int, pin_handler: int, can_handler: int, scheduler: int) -> MAVLink_sys_tm_message:
+        """
+        System status telemetry
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        logger                    : True if the logger started correctly (type:uint8_t)
+        event_broker              : True if the event broker started correctly (type:uint8_t)
+        radio                     : True if the radio started correctly (type:uint8_t)
+        sensors                   : True if the sensors started correctly (type:uint8_t)
+        actuators                 : True if the sensors started correctly (type:uint8_t)
+        pin_handler               : True if the pin observer started correctly (type:uint8_t)
+        can_handler               : True if the can handler started correctly (type:uint8_t)
+        scheduler                 : True if the board scheduler is running (type:uint8_t)
+
+        """
+        return MAVLink_sys_tm_message(timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler)
+
+    def sys_tm_send(self, timestamp: int, logger: int, event_broker: int, radio: int, sensors: int, actuators: int, pin_handler: int, can_handler: int, scheduler: int, force_mavlink1: bool = False) -> None:
+        """
+        System status telemetry
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        logger                    : True if the logger started correctly (type:uint8_t)
+        event_broker              : True if the event broker started correctly (type:uint8_t)
+        radio                     : True if the radio started correctly (type:uint8_t)
+        sensors                   : True if the sensors started correctly (type:uint8_t)
+        actuators                 : True if the sensors started correctly (type:uint8_t)
+        pin_handler               : True if the pin observer started correctly (type:uint8_t)
+        can_handler               : True if the can handler started correctly (type:uint8_t)
+        scheduler                 : True if the board scheduler is running (type:uint8_t)
+
+        """
+        self.send(self.sys_tm_encode(timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler), force_mavlink1=force_mavlink1)
+
+    def logger_tm_encode(self, timestamp: int, log_number: int, too_large_samples: int, dropped_samples: int, queued_samples: int, buffers_filled: int, buffers_written: int, writes_failed: int, last_write_error: int, average_write_time: int, max_write_time: int) -> MAVLink_logger_tm_message:
+        """
+        Logger status telemetry
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+        too_large_samples         : Number of dropped samples because too large (type:int32_t)
+        dropped_samples           : Number of dropped samples due to fifo full (type:int32_t)
+        queued_samples            : Number of samples written to buffer (type:int32_t)
+        buffers_filled            : Number of buffers filled (type:int32_t)
+        buffers_written           : Number of buffers written to disk (type:int32_t)
+        writes_failed             : Number of fwrite() that failed (type:int32_t)
+        last_write_error          : Error of the last fwrite() that failed (type:int32_t)
+        average_write_time        : Average time to perform an fwrite() of a buffer (type:int32_t)
+        max_write_time            : Max time to perform an fwrite() of a buffer (type:int32_t)
+
+        """
+        return MAVLink_logger_tm_message(timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time)
+
+    def logger_tm_send(self, timestamp: int, log_number: int, too_large_samples: int, dropped_samples: int, queued_samples: int, buffers_filled: int, buffers_written: int, writes_failed: int, last_write_error: int, average_write_time: int, max_write_time: int, force_mavlink1: bool = False) -> None:
+        """
+        Logger status telemetry
+
+        timestamp                 : Timestamp [us] (type:uint64_t)
+        log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+        too_large_samples         : Number of dropped samples because too large (type:int32_t)
+        dropped_samples           : Number of dropped samples due to fifo full (type:int32_t)
+        queued_samples            : Number of samples written to buffer (type:int32_t)
+        buffers_filled            : Number of buffers filled (type:int32_t)
+        buffers_written           : Number of buffers written to disk (type:int32_t)
+        writes_failed             : Number of fwrite() that failed (type:int32_t)
+        last_write_error          : Error of the last fwrite() that failed (type:int32_t)
+        average_write_time        : Average time to perform an fwrite() of a buffer (type:int32_t)
+        max_write_time            : Max time to perform an fwrite() of a buffer (type:int32_t)
+
+        """
+        self.send(self.logger_tm_encode(timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time), force_mavlink1=force_mavlink1)
+
+    def mavlink_stats_tm_encode(self, timestamp: int, n_send_queue: int, max_send_queue: int, n_send_errors: int, msg_received: int, buffer_overrun: int, parse_error: int, parse_state: int, packet_idx: int, current_rx_seq: int, current_tx_seq: int, packet_rx_success_count: int, packet_rx_drop_count: int) -> MAVLink_mavlink_stats_tm_message:
+        """
+        Status of MavlinkDriver
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        n_send_queue              : Current len of the occupied portion of the queue (type:uint16_t)
+        max_send_queue            : Max occupied len of the queue (type:uint16_t)
+        n_send_errors             : Number of packet not sent correctly by the TMTC (type:uint16_t)
+        msg_received              : Number of received messages (type:uint8_t)
+        buffer_overrun            : Number of buffer overruns (type:uint8_t)
+        parse_error               : Number of parse errors (type:uint8_t)
+        parse_state               : Parsing state machine (type:uint32_t)
+        packet_idx                : Index in current packet (type:uint8_t)
+        current_rx_seq            : Sequence number of last packet received (type:uint8_t)
+        current_tx_seq            : Sequence number of last packet sent (type:uint8_t)
+        packet_rx_success_count        : Received packets (type:uint16_t)
+        packet_rx_drop_count        : Number of packet drops (type:uint16_t)
+
+        """
+        return MAVLink_mavlink_stats_tm_message(timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count)
+
+    def mavlink_stats_tm_send(self, timestamp: int, n_send_queue: int, max_send_queue: int, n_send_errors: int, msg_received: int, buffer_overrun: int, parse_error: int, parse_state: int, packet_idx: int, current_rx_seq: int, current_tx_seq: int, packet_rx_success_count: int, packet_rx_drop_count: int, force_mavlink1: bool = False) -> None:
+        """
+        Status of MavlinkDriver
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        n_send_queue              : Current len of the occupied portion of the queue (type:uint16_t)
+        max_send_queue            : Max occupied len of the queue (type:uint16_t)
+        n_send_errors             : Number of packet not sent correctly by the TMTC (type:uint16_t)
+        msg_received              : Number of received messages (type:uint8_t)
+        buffer_overrun            : Number of buffer overruns (type:uint8_t)
+        parse_error               : Number of parse errors (type:uint8_t)
+        parse_state               : Parsing state machine (type:uint32_t)
+        packet_idx                : Index in current packet (type:uint8_t)
+        current_rx_seq            : Sequence number of last packet received (type:uint8_t)
+        current_tx_seq            : Sequence number of last packet sent (type:uint8_t)
+        packet_rx_success_count        : Received packets (type:uint16_t)
+        packet_rx_drop_count        : Number of packet drops (type:uint16_t)
+
+        """
+        self.send(self.mavlink_stats_tm_encode(timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count), force_mavlink1=force_mavlink1)
+
+    def can_stats_tm_encode(self, timestamp: int, payload_bit_rate: float, total_bit_rate: float, load_percent: float) -> MAVLink_can_stats_tm_message:
+        """
+        Status of CanHandler
 
-        def sensor_state_tm_send(self, sensor_name, initialized, enabled, force_mavlink1=False):
-                '''
-                
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        payload_bit_rate          : Payload only bitrate (type:float)
+        total_bit_rate            : Total bitrate (type:float)
+        load_percent              : Load percent of the BUS (type:float)
 
-                sensor_name               : Sensor name (type:char)
-                initialized               : Boolean that represents the init state (type:uint8_t)
-                enabled                   : Boolean that represents the enabled state (type:uint8_t)
+        """
+        return MAVLink_can_stats_tm_message(timestamp, payload_bit_rate, total_bit_rate, load_percent)
 
-                '''
-                return self.send(self.sensor_state_tm_encode(sensor_name, initialized, enabled), force_mavlink1=force_mavlink1)
+    def can_stats_tm_send(self, timestamp: int, payload_bit_rate: float, total_bit_rate: float, load_percent: float, force_mavlink1: bool = False) -> None:
+        """
+        Status of CanHandler
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        payload_bit_rate          : Payload only bitrate (type:float)
+        total_bit_rate            : Total bitrate (type:float)
+        load_percent              : Load percent of the BUS (type:float)
 
-        def servo_tm_encode(self, servo_id, servo_position):
-                '''
-                
+        """
+        self.send(self.can_stats_tm_encode(timestamp, payload_bit_rate, total_bit_rate, load_percent), force_mavlink1=force_mavlink1)
 
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
-                servo_position            : Position of the servo [0-1] (type:float)
+    def task_stats_tm_encode(self, timestamp: int, task_id: int, task_period: int, task_missed_events: int, task_failed_events: int, task_activation_mean: float, task_activation_stddev: float, task_period_mean: float, task_period_stddev: float, task_workload_mean: float, task_workload_stddev: float) -> MAVLink_task_stats_tm_message:
+        """
+        Statistics of the Task Scheduler
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        task_id                   : Task ID (type:uint16_t)
+        task_period               : Period of the task [ns] (type:uint16_t)
+        task_missed_events        : Number of missed events (type:uint32_t)
+        task_failed_events        : Number of missed events (type:uint32_t)
+        task_activation_mean        : Task activation mean period (type:float)
+        task_activation_stddev        : Task activation mean standard deviation (type:float)
+        task_period_mean          : Task period mean period (type:float)
+        task_period_stddev        : Task period mean standard deviation (type:float)
+        task_workload_mean        : Task workload mean period (type:float)
+        task_workload_stddev        : Task workload mean standard deviation (type:float)
+
+        """
+        return MAVLink_task_stats_tm_message(timestamp, task_id, task_period, task_missed_events, task_failed_events, task_activation_mean, task_activation_stddev, task_period_mean, task_period_stddev, task_workload_mean, task_workload_stddev)
+
+    def task_stats_tm_send(self, timestamp: int, task_id: int, task_period: int, task_missed_events: int, task_failed_events: int, task_activation_mean: float, task_activation_stddev: float, task_period_mean: float, task_period_stddev: float, task_workload_mean: float, task_workload_stddev: float, force_mavlink1: bool = False) -> None:
+        """
+        Statistics of the Task Scheduler
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        task_id                   : Task ID (type:uint16_t)
+        task_period               : Period of the task [ns] (type:uint16_t)
+        task_missed_events        : Number of missed events (type:uint32_t)
+        task_failed_events        : Number of missed events (type:uint32_t)
+        task_activation_mean        : Task activation mean period (type:float)
+        task_activation_stddev        : Task activation mean standard deviation (type:float)
+        task_period_mean          : Task period mean period (type:float)
+        task_period_stddev        : Task period mean standard deviation (type:float)
+        task_workload_mean        : Task workload mean period (type:float)
+        task_workload_stddev        : Task workload mean standard deviation (type:float)
+
+        """
+        self.send(self.task_stats_tm_encode(timestamp, task_id, task_period, task_missed_events, task_failed_events, task_activation_mean, task_activation_stddev, task_period_mean, task_period_stddev, task_workload_mean, task_workload_stddev), force_mavlink1=force_mavlink1)
+
+    def ada_tm_encode(self, timestamp: int, state: int, kalman_x0: float, kalman_x1: float, kalman_x2: float, vertical_speed: float, msl_altitude: float, ref_pressure: float, ref_altitude: float, ref_temperature: float, msl_pressure: float, msl_temperature: float, dpl_altitude: float) -> MAVLink_ada_tm_message:
+        """
+        Apogee Detection Algorithm status telemetry
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        state                     : ADA current state (type:uint8_t)
+        kalman_x0                 : Kalman state variable 0 (pressure) (type:float)
+        kalman_x1                 : Kalman state variable 1 (pressure velocity) (type:float)
+        kalman_x2                 : Kalman state variable 2 (pressure acceleration) (type:float)
+        vertical_speed            : Vertical speed computed by the ADA [m/s] (type:float)
+        msl_altitude              : Altitude w.r.t. mean sea level [m] (type:float)
+        ref_pressure              : Calibration pressure [Pa] (type:float)
+        ref_altitude              : Calibration altitude [m] (type:float)
+        ref_temperature           : Calibration temperature [degC] (type:float)
+        msl_pressure              : Expected pressure at mean sea level [Pa] (type:float)
+        msl_temperature           : Expected temperature at mean sea level [degC] (type:float)
+        dpl_altitude              : Main parachute deployment altituyde [m] (type:float)
+
+        """
+        return MAVLink_ada_tm_message(timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude)
+
+    def ada_tm_send(self, timestamp: int, state: int, kalman_x0: float, kalman_x1: float, kalman_x2: float, vertical_speed: float, msl_altitude: float, ref_pressure: float, ref_altitude: float, ref_temperature: float, msl_pressure: float, msl_temperature: float, dpl_altitude: float, force_mavlink1: bool = False) -> None:
+        """
+        Apogee Detection Algorithm status telemetry
 
-                '''
-                return MAVLink_servo_tm_message(servo_id, servo_position)
-
-        def servo_tm_send(self, servo_id, servo_position, force_mavlink1=False):
-                '''
-                
-
-                servo_id                  : A member of the ServosList enum (type:uint8_t)
-                servo_position            : Position of the servo [0-1] (type:float)
-
-                '''
-                return self.send(self.servo_tm_encode(servo_id, servo_position), force_mavlink1=force_mavlink1)
-
-        def pin_tm_encode(self, timestamp, pin_id, last_change_timestamp, changes_counter, current_state):
-                '''
-                
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                pin_id                    : A member of the PinsList enum (type:uint8_t)
-                last_change_timestamp        : Last change timestamp of pin (type:uint64_t)
-                changes_counter           : Number of changes of pin (type:uint8_t)
-                current_state             : Current state of pin (type:uint8_t)
-
-                '''
-                return MAVLink_pin_tm_message(timestamp, pin_id, last_change_timestamp, changes_counter, current_state)
-
-        def pin_tm_send(self, timestamp, pin_id, last_change_timestamp, changes_counter, current_state, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                pin_id                    : A member of the PinsList enum (type:uint8_t)
-                last_change_timestamp        : Last change timestamp of pin (type:uint64_t)
-                changes_counter           : Number of changes of pin (type:uint8_t)
-                current_state             : Current state of pin (type:uint8_t)
-
-                '''
-                return self.send(self.pin_tm_encode(timestamp, pin_id, last_change_timestamp, changes_counter, current_state), force_mavlink1=force_mavlink1)
-
-        def registry_float_tm_encode(self, timestamp, key_id, key_name, value):
-                '''
-                
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                key_id                    : Id of this configuration entry (type:uint32_t)
-                key_name                  : Name of this configuration entry (type:char)
-                value                     : Value of this configuration (type:float)
-
-                '''
-                return MAVLink_registry_float_tm_message(timestamp, key_id, key_name, value)
-
-        def registry_float_tm_send(self, timestamp, key_id, key_name, value, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                key_id                    : Id of this configuration entry (type:uint32_t)
-                key_name                  : Name of this configuration entry (type:char)
-                value                     : Value of this configuration (type:float)
-
-                '''
-                return self.send(self.registry_float_tm_encode(timestamp, key_id, key_name, value), force_mavlink1=force_mavlink1)
-
-        def registry_int_tm_encode(self, timestamp, key_id, key_name, value):
-                '''
-                
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                key_id                    : Id of this configuration entry (type:uint32_t)
-                key_name                  : Name of this configuration entry (type:char)
-                value                     : Value of this configuration (type:uint32_t)
-
-                '''
-                return MAVLink_registry_int_tm_message(timestamp, key_id, key_name, value)
-
-        def registry_int_tm_send(self, timestamp, key_id, key_name, value, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                key_id                    : Id of this configuration entry (type:uint32_t)
-                key_name                  : Name of this configuration entry (type:char)
-                value                     : Value of this configuration (type:uint32_t)
-
-                '''
-                return self.send(self.registry_int_tm_encode(timestamp, key_id, key_name, value), force_mavlink1=force_mavlink1)
-
-        def registry_coord_tm_encode(self, timestamp, key_id, key_name, latitude, longitude):
-                '''
-                
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                key_id                    : Id of this configuration entry (type:uint32_t)
-                key_name                  : Name of this configuration entry (type:char)
-                latitude                  : Latitude in this configuration [deg] (type:float)
-                longitude                 : Latitude in this configuration [deg] (type:float)
-
-                '''
-                return MAVLink_registry_coord_tm_message(timestamp, key_id, key_name, latitude, longitude)
-
-        def registry_coord_tm_send(self, timestamp, key_id, key_name, latitude, longitude, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                key_id                    : Id of this configuration entry (type:uint32_t)
-                key_name                  : Name of this configuration entry (type:char)
-                latitude                  : Latitude in this configuration [deg] (type:float)
-                longitude                 : Latitude in this configuration [deg] (type:float)
-
-                '''
-                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, 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):
-                '''
-                
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                yaw                       : Current Yaw [deg] (type:float)
-                pitch                     : Current Pitch [deg] (type:float)
-                roll                      : Current Roll [deg] (type:float)
-                target_yaw                : Target Yaw [deg] (type:float)
-                target_pitch              : Target Pitch [deg] (type:float)
-                stepperX_pos              : StepperX current position wrt the boot position [deg] (type:float)
-                stepperX_delta            : StepperX last actuated delta angle [deg] (type:float)
-                stepperX_speed            : StepperX current speed [rps] (type:float)
-                stepperY_pos              : StepperY current position wrt the boot position [deg] (type:float)
-                stepperY_delta            : StepperY last actuated delta angle [deg] (type:float)
-                stepperY_speed            : StepperY current Speed [rps] (type:float)
-                gps_latitude              : Latitude [deg] (type:float)
-                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)
-
-                '''
-                return MAVLink_arp_tm_message(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, 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)
-
-        def arp_tm_send(self, 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, 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, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                yaw                       : Current Yaw [deg] (type:float)
-                pitch                     : Current Pitch [deg] (type:float)
-                roll                      : Current Roll [deg] (type:float)
-                target_yaw                : Target Yaw [deg] (type:float)
-                target_pitch              : Target Pitch [deg] (type:float)
-                stepperX_pos              : StepperX current position wrt the boot position [deg] (type:float)
-                stepperX_delta            : StepperX last actuated delta angle [deg] (type:float)
-                stepperX_speed            : StepperX current speed [rps] (type:float)
-                stepperY_pos              : StepperY current position wrt the boot position [deg] (type:float)
-                stepperY_delta            : StepperY last actuated delta angle [deg] (type:float)
-                stepperY_speed            : StepperY current Speed [rps] (type:float)
-                gps_latitude              : Latitude [deg] (type:float)
-                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)
-
-                '''
-                return self.send(self.arp_tm_encode(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, 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), force_mavlink1=force_mavlink1)
-
-        def set_antenna_coordinates_arp_tc_encode(self, latitude, longitude):
-                '''
-                Sets current antennas coordinates
-
-                latitude                  : Latitude [deg] (type:float)
-                longitude                 : Longitude [deg] (type:float)
-
-                '''
-                return MAVLink_set_antenna_coordinates_arp_tc_message(latitude, longitude)
-
-        def set_antenna_coordinates_arp_tc_send(self, latitude, longitude, force_mavlink1=False):
-                '''
-                Sets current antennas coordinates
-
-                latitude                  : Latitude [deg] (type:float)
-                longitude                 : Longitude [deg] (type:float)
-
-                '''
-                return self.send(self.set_antenna_coordinates_arp_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1)
-
-        def set_rocket_coordinates_arp_tc_encode(self, latitude, longitude):
-                '''
-                Sets current rocket coordinates
-
-                latitude                  : Latitude [deg] (type:float)
-                longitude                 : Longitude [deg] (type:float)
-
-                '''
-                return MAVLink_set_rocket_coordinates_arp_tc_message(latitude, longitude)
-
-        def set_rocket_coordinates_arp_tc_send(self, latitude, longitude, force_mavlink1=False):
-                '''
-                Sets current rocket coordinates
-
-                latitude                  : Latitude [deg] (type:float)
-                longitude                 : Longitude [deg] (type:float)
-
-                '''
-                return self.send(self.set_rocket_coordinates_arp_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1)
-
-        def sys_tm_encode(self, timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler):
-                '''
-                System status telemetry
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                logger                    : True if the logger started correctly (type:uint8_t)
-                event_broker              : True if the event broker started correctly (type:uint8_t)
-                radio                     : True if the radio started correctly (type:uint8_t)
-                sensors                   : True if the sensors started correctly (type:uint8_t)
-                actuators                 : True if the sensors started correctly (type:uint8_t)
-                pin_handler               : True if the pin observer started correctly (type:uint8_t)
-                can_handler               : True if the can handler started correctly (type:uint8_t)
-                scheduler                 : True if the board scheduler is running (type:uint8_t)
-
-                '''
-                return MAVLink_sys_tm_message(timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler)
-
-        def sys_tm_send(self, timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler, force_mavlink1=False):
-                '''
-                System status telemetry
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                logger                    : True if the logger started correctly (type:uint8_t)
-                event_broker              : True if the event broker started correctly (type:uint8_t)
-                radio                     : True if the radio started correctly (type:uint8_t)
-                sensors                   : True if the sensors started correctly (type:uint8_t)
-                actuators                 : True if the sensors started correctly (type:uint8_t)
-                pin_handler               : True if the pin observer started correctly (type:uint8_t)
-                can_handler               : True if the can handler started correctly (type:uint8_t)
-                scheduler                 : True if the board scheduler is running (type:uint8_t)
-
-                '''
-                return self.send(self.sys_tm_encode(timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler), force_mavlink1=force_mavlink1)
-
-        def logger_tm_encode(self, timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time):
-                '''
-                Logger status telemetry
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
-                too_large_samples         : Number of dropped samples because too large (type:int32_t)
-                dropped_samples           : Number of dropped samples due to fifo full (type:int32_t)
-                queued_samples            : Number of samples written to buffer (type:int32_t)
-                buffers_filled            : Number of buffers filled (type:int32_t)
-                buffers_written           : Number of buffers written to disk (type:int32_t)
-                writes_failed             : Number of fwrite() that failed (type:int32_t)
-                last_write_error          : Error of the last fwrite() that failed (type:int32_t)
-                average_write_time        : Average time to perform an fwrite() of a buffer (type:int32_t)
-                max_write_time            : Max time to perform an fwrite() of a buffer (type:int32_t)
-
-                '''
-                return MAVLink_logger_tm_message(timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time)
-
-        def logger_tm_send(self, timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time, force_mavlink1=False):
-                '''
-                Logger status telemetry
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
-                too_large_samples         : Number of dropped samples because too large (type:int32_t)
-                dropped_samples           : Number of dropped samples due to fifo full (type:int32_t)
-                queued_samples            : Number of samples written to buffer (type:int32_t)
-                buffers_filled            : Number of buffers filled (type:int32_t)
-                buffers_written           : Number of buffers written to disk (type:int32_t)
-                writes_failed             : Number of fwrite() that failed (type:int32_t)
-                last_write_error          : Error of the last fwrite() that failed (type:int32_t)
-                average_write_time        : Average time to perform an fwrite() of a buffer (type:int32_t)
-                max_write_time            : Max time to perform an fwrite() of a buffer (type:int32_t)
-
-                '''
-                return self.send(self.logger_tm_encode(timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time), force_mavlink1=force_mavlink1)
-
-        def mavlink_stats_tm_encode(self, timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count):
-                '''
-                Status of MavlinkDriver
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                n_send_queue              : Current len of the occupied portion of the queue (type:uint16_t)
-                max_send_queue            : Max occupied len of the queue (type:uint16_t)
-                n_send_errors             : Number of packet not sent correctly by the TMTC (type:uint16_t)
-                msg_received              : Number of received messages (type:uint8_t)
-                buffer_overrun            : Number of buffer overruns (type:uint8_t)
-                parse_error               : Number of parse errors (type:uint8_t)
-                parse_state               : Parsing state machine (type:uint32_t)
-                packet_idx                : Index in current packet (type:uint8_t)
-                current_rx_seq            : Sequence number of last packet received (type:uint8_t)
-                current_tx_seq            : Sequence number of last packet sent (type:uint8_t)
-                packet_rx_success_count        : Received packets (type:uint16_t)
-                packet_rx_drop_count        : Number of packet drops (type:uint16_t)
-
-                '''
-                return MAVLink_mavlink_stats_tm_message(timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count)
-
-        def mavlink_stats_tm_send(self, timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count, force_mavlink1=False):
-                '''
-                Status of MavlinkDriver
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                n_send_queue              : Current len of the occupied portion of the queue (type:uint16_t)
-                max_send_queue            : Max occupied len of the queue (type:uint16_t)
-                n_send_errors             : Number of packet not sent correctly by the TMTC (type:uint16_t)
-                msg_received              : Number of received messages (type:uint8_t)
-                buffer_overrun            : Number of buffer overruns (type:uint8_t)
-                parse_error               : Number of parse errors (type:uint8_t)
-                parse_state               : Parsing state machine (type:uint32_t)
-                packet_idx                : Index in current packet (type:uint8_t)
-                current_rx_seq            : Sequence number of last packet received (type:uint8_t)
-                current_tx_seq            : Sequence number of last packet sent (type:uint8_t)
-                packet_rx_success_count        : Received packets (type:uint16_t)
-                packet_rx_drop_count        : Number of packet drops (type:uint16_t)
-
-                '''
-                return self.send(self.mavlink_stats_tm_encode(timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count), force_mavlink1=force_mavlink1)
-
-        def can_stats_tm_encode(self, timestamp, payload_bit_rate, total_bit_rate, load_percent):
-                '''
-                Status of CanHandler
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                payload_bit_rate          : Payload only bitrate (type:float)
-                total_bit_rate            : Total bitrate (type:float)
-                load_percent              : Load percent of the BUS (type:float)
-
-                '''
-                return MAVLink_can_stats_tm_message(timestamp, payload_bit_rate, total_bit_rate, load_percent)
-
-        def can_stats_tm_send(self, timestamp, payload_bit_rate, total_bit_rate, load_percent, force_mavlink1=False):
-                '''
-                Status of CanHandler
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                payload_bit_rate          : Payload only bitrate (type:float)
-                total_bit_rate            : Total bitrate (type:float)
-                load_percent              : Load percent of the BUS (type:float)
-
-                '''
-                return self.send(self.can_stats_tm_encode(timestamp, payload_bit_rate, total_bit_rate, load_percent), force_mavlink1=force_mavlink1)
-
-        def task_stats_tm_encode(self, timestamp, task_id, task_period, task_missed_events, task_failed_events, task_activation_mean, task_activation_stddev, task_period_mean, task_period_stddev, task_workload_mean, task_workload_stddev):
-                '''
-                Statistics of the Task Scheduler
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                task_id                   : Task ID (type:uint16_t)
-                task_period               : Period of the task [ns] (type:uint16_t)
-                task_missed_events        : Number of missed events (type:uint32_t)
-                task_failed_events        : Number of missed events (type:uint32_t)
-                task_activation_mean        : Task activation mean period (type:float)
-                task_activation_stddev        : Task activation mean standard deviation (type:float)
-                task_period_mean          : Task period mean period (type:float)
-                task_period_stddev        : Task period mean standard deviation (type:float)
-                task_workload_mean        : Task workload mean period (type:float)
-                task_workload_stddev        : Task workload mean standard deviation (type:float)
-
-                '''
-                return MAVLink_task_stats_tm_message(timestamp, task_id, task_period, task_missed_events, task_failed_events, task_activation_mean, task_activation_stddev, task_period_mean, task_period_stddev, task_workload_mean, task_workload_stddev)
-
-        def task_stats_tm_send(self, timestamp, task_id, task_period, task_missed_events, task_failed_events, task_activation_mean, task_activation_stddev, task_period_mean, task_period_stddev, task_workload_mean, task_workload_stddev, force_mavlink1=False):
-                '''
-                Statistics of the Task Scheduler
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                task_id                   : Task ID (type:uint16_t)
-                task_period               : Period of the task [ns] (type:uint16_t)
-                task_missed_events        : Number of missed events (type:uint32_t)
-                task_failed_events        : Number of missed events (type:uint32_t)
-                task_activation_mean        : Task activation mean period (type:float)
-                task_activation_stddev        : Task activation mean standard deviation (type:float)
-                task_period_mean          : Task period mean period (type:float)
-                task_period_stddev        : Task period mean standard deviation (type:float)
-                task_workload_mean        : Task workload mean period (type:float)
-                task_workload_stddev        : Task workload mean standard deviation (type:float)
-
-                '''
-                return self.send(self.task_stats_tm_encode(timestamp, task_id, task_period, task_missed_events, task_failed_events, task_activation_mean, task_activation_stddev, task_period_mean, task_period_stddev, task_workload_mean, task_workload_stddev), force_mavlink1=force_mavlink1)
-
-        def ada_tm_encode(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude):
-                '''
-                Apogee Detection Algorithm status telemetry
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                state                     : ADA current state (type:uint8_t)
-                kalman_x0                 : Kalman state variable 0 (pressure) (type:float)
-                kalman_x1                 : Kalman state variable 1 (pressure velocity) (type:float)
-                kalman_x2                 : Kalman state variable 2 (pressure acceleration) (type:float)
-                vertical_speed            : Vertical speed computed by the ADA [m/s] (type:float)
-                msl_altitude              : Altitude w.r.t. mean sea level [m] (type:float)
-                ref_pressure              : Calibration pressure [Pa] (type:float)
-                ref_altitude              : Calibration altitude [m] (type:float)
-                ref_temperature           : Calibration temperature [degC] (type:float)
-                msl_pressure              : Expected pressure at mean sea level [Pa] (type:float)
-                msl_temperature           : Expected temperature at mean sea level [degC] (type:float)
-                dpl_altitude              : Main parachute deployment altituyde [m] (type:float)
-
-                '''
-                return MAVLink_ada_tm_message(timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude)
-
-        def ada_tm_send(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude, force_mavlink1=False):
-                '''
-                Apogee Detection Algorithm status telemetry
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                state                     : ADA current state (type:uint8_t)
-                kalman_x0                 : Kalman state variable 0 (pressure) (type:float)
-                kalman_x1                 : Kalman state variable 1 (pressure velocity) (type:float)
-                kalman_x2                 : Kalman state variable 2 (pressure acceleration) (type:float)
-                vertical_speed            : Vertical speed computed by the ADA [m/s] (type:float)
-                msl_altitude              : Altitude w.r.t. mean sea level [m] (type:float)
-                ref_pressure              : Calibration pressure [Pa] (type:float)
-                ref_altitude              : Calibration altitude [m] (type:float)
-                ref_temperature           : Calibration temperature [degC] (type:float)
-                msl_pressure              : Expected pressure at mean sea level [Pa] (type:float)
-                msl_temperature           : Expected temperature at mean sea level [degC] (type:float)
-                dpl_altitude              : Main parachute deployment altituyde [m] (type:float)
-
-                '''
-                return self.send(self.ada_tm_encode(timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude), force_mavlink1=force_mavlink1)
-
-        def nas_tm_encode(self, timestamp, state, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, ref_pressure, ref_temperature, ref_latitude, ref_longitude):
-                '''
-                Navigation System status telemetry
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                state                     : NAS current state (type:uint8_t)
-                nas_n                     : Navigation system estimated noth position [deg] (type:float)
-                nas_e                     : Navigation system estimated east position [deg] (type:float)
-                nas_d                     : Navigation system estimated down position [m] (type:float)
-                nas_vn                    : Navigation system estimated north velocity [m/s] (type:float)
-                nas_ve                    : Navigation system estimated east velocity [m/s] (type:float)
-                nas_vd                    : Navigation system estimated down velocity [m/s] (type:float)
-                nas_qx                    : Navigation system estimated attitude (qx) [deg] (type:float)
-                nas_qy                    : Navigation system estimated attitude (qy) [deg] (type:float)
-                nas_qz                    : Navigation system estimated attitude (qz) [deg] (type:float)
-                nas_qw                    : Navigation system estimated attitude (qw) [deg] (type:float)
-                nas_bias_x                : Navigation system gyroscope bias on x axis (type:float)
-                nas_bias_y                : Navigation system gyroscope bias on y axis (type:float)
-                nas_bias_z                : Navigation system gyroscope bias on z axis (type:float)
-                ref_pressure              : Calibration pressure [Pa] (type:float)
-                ref_temperature           : Calibration temperature [degC] (type:float)
-                ref_latitude              : Calibration latitude [deg] (type:float)
-                ref_longitude             : Calibration longitude [deg] (type:float)
-
-                '''
-                return MAVLink_nas_tm_message(timestamp, state, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, ref_pressure, ref_temperature, ref_latitude, ref_longitude)
-
-        def nas_tm_send(self, timestamp, state, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, ref_pressure, ref_temperature, ref_latitude, ref_longitude, force_mavlink1=False):
-                '''
-                Navigation System status telemetry
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                state                     : NAS current state (type:uint8_t)
-                nas_n                     : Navigation system estimated noth position [deg] (type:float)
-                nas_e                     : Navigation system estimated east position [deg] (type:float)
-                nas_d                     : Navigation system estimated down position [m] (type:float)
-                nas_vn                    : Navigation system estimated north velocity [m/s] (type:float)
-                nas_ve                    : Navigation system estimated east velocity [m/s] (type:float)
-                nas_vd                    : Navigation system estimated down velocity [m/s] (type:float)
-                nas_qx                    : Navigation system estimated attitude (qx) [deg] (type:float)
-                nas_qy                    : Navigation system estimated attitude (qy) [deg] (type:float)
-                nas_qz                    : Navigation system estimated attitude (qz) [deg] (type:float)
-                nas_qw                    : Navigation system estimated attitude (qw) [deg] (type:float)
-                nas_bias_x                : Navigation system gyroscope bias on x axis (type:float)
-                nas_bias_y                : Navigation system gyroscope bias on y axis (type:float)
-                nas_bias_z                : Navigation system gyroscope bias on z axis (type:float)
-                ref_pressure              : Calibration pressure [Pa] (type:float)
-                ref_temperature           : Calibration temperature [degC] (type:float)
-                ref_latitude              : Calibration latitude [deg] (type:float)
-                ref_longitude             : Calibration longitude [deg] (type:float)
-
-                '''
-                return self.send(self.nas_tm_encode(timestamp, state, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, ref_pressure, ref_temperature, ref_latitude, ref_longitude), force_mavlink1=force_mavlink1)
-
-        def mea_tm_encode(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure):
-                '''
-                Mass Estimation Algorithm status telemetry
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                state                     : MEA current state (type:uint8_t)
-                kalman_x0                 : Kalman state variable 0 (corrected pressure) (type:float)
-                kalman_x1                 : Kalman state variable 1 (type:float)
-                kalman_x2                 : Kalman state variable 2 (mass) (type:float)
-                mass                      : Mass estimated [kg] (type:float)
-                corrected_pressure        : Corrected pressure [Pa] (type:float)
-
-                '''
-                return MAVLink_mea_tm_message(timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure)
-
-        def mea_tm_send(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure, force_mavlink1=False):
-                '''
-                Mass Estimation Algorithm status telemetry
-
-                timestamp                 : When was this logged [us] (type:uint64_t)
-                state                     : MEA current state (type:uint8_t)
-                kalman_x0                 : Kalman state variable 0 (corrected pressure) (type:float)
-                kalman_x1                 : Kalman state variable 1 (type:float)
-                kalman_x2                 : Kalman state variable 2 (mass) (type:float)
-                mass                      : Mass estimated [kg] (type:float)
-                corrected_pressure        : Corrected pressure [Pa] (type:float)
-
-                '''
-                return self.send(self.mea_tm_encode(timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure), force_mavlink1=force_mavlink1)
-
-        def rocket_flight_tm_encode(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, temperature, payload_can_status, motor_can_status, rig_can_status):
-                '''
-                High Rate Telemetry
-
-                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
-                ada_state                 : ADA Controller State (type:uint8_t)
-                fmm_state                 : Flight Mode Manager State (type:uint8_t)
-                dpl_state                 : Deployment Controller State (type:uint8_t)
-                abk_state                 : Airbrake FSM state (type:uint8_t)
-                nas_state                 : NAS FSM State (type:uint8_t)
-                mea_state                 : MEA Controller State (type:uint8_t)
-                pressure_ada              : Atmospheric pressure estimated by ADA [Pa] (type:float)
-                pressure_digi             : Pressure from digital sensor [Pa] (type:float)
-                pressure_static           : Pressure from static port [Pa] (type:float)
-                pressure_dpl              : Pressure from deployment vane sensor [Pa] (type:float)
-                airspeed_pitot            : Pitot airspeed [m/s] (type:float)
-                altitude_agl              : Altitude above ground level [m] (type:float)
-                ada_vert_speed            : Vertical speed estimated by ADA [m/s] (type:float)
-                mea_mass                  : Mass estimated by MEA [kg] (type:float)
-                acc_x                     : Acceleration on X axis (body) [m/s^2] (type:float)
-                acc_y                     : Acceleration on Y axis (body) [m/s^2] (type:float)
-                acc_z                     : Acceleration on Z axis (body) [m/s^2] (type:float)
-                gyro_x                    : Angular speed on X axis (body) [rad/s] (type:float)
-                gyro_y                    : Angular speed on Y axis (body) [rad/s] (type:float)
-                gyro_z                    : Angular speed on Z axis (body) [rad/s] (type:float)
-                mag_x                     : Magnetic field on X axis (body) [uT] (type:float)
-                mag_y                     : Magnetic field on Y axis (body) [uT] (type:float)
-                mag_z                     : Magnetic field on Z axis (body) [uT] (type:float)
-                gps_fix                   : GPS fix (1 = fix, 0 = no fix) (type:uint8_t)
-                gps_lat                   : Latitude [deg] (type:float)
-                gps_lon                   : Longitude [deg] (type:float)
-                gps_alt                   : GPS Altitude [m] (type:float)
-                abk_angle                 : Air Brakes angle [deg] (type:float)
-                nas_n                     : NAS estimated noth position [deg] (type:float)
-                nas_e                     : NAS estimated east position [deg] (type:float)
-                nas_d                     : NAS estimated down position [m] (type:float)
-                nas_vn                    : NAS estimated north velocity [m/s] (type:float)
-                nas_ve                    : NAS estimated east velocity [m/s] (type:float)
-                nas_vd                    : NAS estimated down velocity [m/s] (type:float)
-                nas_qx                    : NAS estimated attitude (qx) [deg] (type:float)
-                nas_qy                    : NAS estimated attitude (qy) [deg] (type:float)
-                nas_qz                    : NAS estimated attitude (qz) [deg] (type:float)
-                nas_qw                    : NAS estimated attitude (qw) [deg] (type:float)
-                nas_bias_x                : NAS gyroscope bias on x axis (type:float)
-                nas_bias_y                : NAS gyroscope bias on y axis (type:float)
-                nas_bias_z                : NAS gyroscope bias on z axis (type:float)
-                pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
-                pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
-                pin_expulsion             : Servo sensor status (1 = actuated, 0 = idle) (type:uint8_t)
-                cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
-                battery_voltage           : Battery voltage [V] (type:float)
-                cam_battery_voltage        : Camera battery voltage [V] (type:float)
-                temperature               : Temperature [degC] (type:float)
-                payload_can_status        : Payload CAN status (type:uint8_t)
-                motor_can_status          : Motor CAN status (type:uint8_t)
-                rig_can_status            : RIG CAN status (type:uint8_t)
-
-                '''
-                return MAVLink_rocket_flight_tm_message(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, temperature, payload_can_status, motor_can_status, rig_can_status)
-
-        def rocket_flight_tm_send(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, temperature, payload_can_status, motor_can_status, rig_can_status, force_mavlink1=False):
-                '''
-                High Rate Telemetry
-
-                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
-                ada_state                 : ADA Controller State (type:uint8_t)
-                fmm_state                 : Flight Mode Manager State (type:uint8_t)
-                dpl_state                 : Deployment Controller State (type:uint8_t)
-                abk_state                 : Airbrake FSM state (type:uint8_t)
-                nas_state                 : NAS FSM State (type:uint8_t)
-                mea_state                 : MEA Controller State (type:uint8_t)
-                pressure_ada              : Atmospheric pressure estimated by ADA [Pa] (type:float)
-                pressure_digi             : Pressure from digital sensor [Pa] (type:float)
-                pressure_static           : Pressure from static port [Pa] (type:float)
-                pressure_dpl              : Pressure from deployment vane sensor [Pa] (type:float)
-                airspeed_pitot            : Pitot airspeed [m/s] (type:float)
-                altitude_agl              : Altitude above ground level [m] (type:float)
-                ada_vert_speed            : Vertical speed estimated by ADA [m/s] (type:float)
-                mea_mass                  : Mass estimated by MEA [kg] (type:float)
-                acc_x                     : Acceleration on X axis (body) [m/s^2] (type:float)
-                acc_y                     : Acceleration on Y axis (body) [m/s^2] (type:float)
-                acc_z                     : Acceleration on Z axis (body) [m/s^2] (type:float)
-                gyro_x                    : Angular speed on X axis (body) [rad/s] (type:float)
-                gyro_y                    : Angular speed on Y axis (body) [rad/s] (type:float)
-                gyro_z                    : Angular speed on Z axis (body) [rad/s] (type:float)
-                mag_x                     : Magnetic field on X axis (body) [uT] (type:float)
-                mag_y                     : Magnetic field on Y axis (body) [uT] (type:float)
-                mag_z                     : Magnetic field on Z axis (body) [uT] (type:float)
-                gps_fix                   : GPS fix (1 = fix, 0 = no fix) (type:uint8_t)
-                gps_lat                   : Latitude [deg] (type:float)
-                gps_lon                   : Longitude [deg] (type:float)
-                gps_alt                   : GPS Altitude [m] (type:float)
-                abk_angle                 : Air Brakes angle [deg] (type:float)
-                nas_n                     : NAS estimated noth position [deg] (type:float)
-                nas_e                     : NAS estimated east position [deg] (type:float)
-                nas_d                     : NAS estimated down position [m] (type:float)
-                nas_vn                    : NAS estimated north velocity [m/s] (type:float)
-                nas_ve                    : NAS estimated east velocity [m/s] (type:float)
-                nas_vd                    : NAS estimated down velocity [m/s] (type:float)
-                nas_qx                    : NAS estimated attitude (qx) [deg] (type:float)
-                nas_qy                    : NAS estimated attitude (qy) [deg] (type:float)
-                nas_qz                    : NAS estimated attitude (qz) [deg] (type:float)
-                nas_qw                    : NAS estimated attitude (qw) [deg] (type:float)
-                nas_bias_x                : NAS gyroscope bias on x axis (type:float)
-                nas_bias_y                : NAS gyroscope bias on y axis (type:float)
-                nas_bias_z                : NAS gyroscope bias on z axis (type:float)
-                pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
-                pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
-                pin_expulsion             : Servo sensor status (1 = actuated, 0 = idle) (type:uint8_t)
-                cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
-                battery_voltage           : Battery voltage [V] (type:float)
-                cam_battery_voltage        : Camera battery voltage [V] (type:float)
-                temperature               : Temperature [degC] (type:float)
-                payload_can_status        : Payload CAN status (type:uint8_t)
-                motor_can_status          : Motor CAN status (type:uint8_t)
-                rig_can_status            : RIG CAN status (type:uint8_t)
-
-                '''
-                return self.send(self.rocket_flight_tm_encode(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, temperature, payload_can_status, motor_can_status, rig_can_status), force_mavlink1=force_mavlink1)
-
-        def payload_flight_tm_encode(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, cutter_presence, temperature, main_can_status, motor_can_status, rig_can_status):
-                '''
-                High Rate Telemetry
-
-                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
-                fmm_state                 : Flight Mode Manager State (type:uint8_t)
-                nas_state                 : NAS FSM State (type:uint8_t)
-                wes_state                 : Wind Estimation System FSM State (type:uint8_t)
-                pressure_digi             : Pressure from digital sensor [Pa] (type:float)
-                pressure_static           : Pressure from static port [Pa] (type:float)
-                airspeed_pitot            : Pitot airspeed [m/s] (type:float)
-                altitude_agl              : Altitude above ground level [m] (type:float)
-                acc_x                     : Acceleration on X axis (body) [m/s^2] (type:float)
-                acc_y                     : Acceleration on Y axis (body) [m/s^2] (type:float)
-                acc_z                     : Acceleration on Z axis (body) [m/s^2] (type:float)
-                gyro_x                    : Angular speed on X axis (body) [rad/s] (type:float)
-                gyro_y                    : Angular speed on Y axis (body) [rad/s] (type:float)
-                gyro_z                    : Angular speed on Z axis (body) [rad/s] (type:float)
-                mag_x                     : Magnetic field on X axis (body) [uT] (type:float)
-                mag_y                     : Magnetic field on Y axis (body) [uT] (type:float)
-                mag_z                     : Magnetic field on Z axis (body) [uT] (type:float)
-                gps_fix                   : GPS fix (1 = fix, 0 = no fix) (type:uint8_t)
-                gps_lat                   : Latitude [deg] (type:float)
-                gps_lon                   : Longitude [deg] (type:float)
-                gps_alt                   : GPS Altitude [m] (type:float)
-                left_servo_angle          : Left servo motor angle [deg] (type:float)
-                right_servo_angle         : Right servo motor angle [deg] (type:float)
-                nas_n                     : NAS estimated noth position [deg] (type:float)
-                nas_e                     : NAS estimated east position [deg] (type:float)
-                nas_d                     : NAS estimated down position [m] (type:float)
-                nas_vn                    : NAS estimated north velocity [m/s] (type:float)
-                nas_ve                    : NAS estimated east velocity [m/s] (type:float)
-                nas_vd                    : NAS estimated down velocity [m/s] (type:float)
-                nas_qx                    : NAS estimated attitude (qx) [deg] (type:float)
-                nas_qy                    : NAS estimated attitude (qy) [deg] (type:float)
-                nas_qz                    : NAS estimated attitude (qz) [deg] (type:float)
-                nas_qw                    : NAS estimated attitude (qw) [deg] (type:float)
-                nas_bias_x                : NAS gyroscope bias on x axis (type:float)
-                nas_bias_y                : NAS gyroscope bias on y axis (type:float)
-                nas_bias_z                : NAS gyroscope bias on z axis (type:float)
-                wes_n                     : Wind estimated north velocity [m/s] (type:float)
-                wes_e                     : Wind estimated east velocity [m/s] (type:float)
-                pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
-                battery_voltage           : Battery voltage [V] (type:float)
-                cam_battery_voltage        : Camera battery voltage [V] (type:float)
-                cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
-                temperature               : Temperature [degC] (type:float)
-                main_can_status           : Main CAN status (type:uint8_t)
-                motor_can_status          : Motor CAN status (type:uint8_t)
-                rig_can_status            : RIG CAN status (type:uint8_t)
-
-                '''
-                return MAVLink_payload_flight_tm_message(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, cutter_presence, temperature, main_can_status, motor_can_status, rig_can_status)
-
-        def payload_flight_tm_send(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, cutter_presence, temperature, main_can_status, motor_can_status, rig_can_status, force_mavlink1=False):
-                '''
-                High Rate Telemetry
-
-                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
-                fmm_state                 : Flight Mode Manager State (type:uint8_t)
-                nas_state                 : NAS FSM State (type:uint8_t)
-                wes_state                 : Wind Estimation System FSM State (type:uint8_t)
-                pressure_digi             : Pressure from digital sensor [Pa] (type:float)
-                pressure_static           : Pressure from static port [Pa] (type:float)
-                airspeed_pitot            : Pitot airspeed [m/s] (type:float)
-                altitude_agl              : Altitude above ground level [m] (type:float)
-                acc_x                     : Acceleration on X axis (body) [m/s^2] (type:float)
-                acc_y                     : Acceleration on Y axis (body) [m/s^2] (type:float)
-                acc_z                     : Acceleration on Z axis (body) [m/s^2] (type:float)
-                gyro_x                    : Angular speed on X axis (body) [rad/s] (type:float)
-                gyro_y                    : Angular speed on Y axis (body) [rad/s] (type:float)
-                gyro_z                    : Angular speed on Z axis (body) [rad/s] (type:float)
-                mag_x                     : Magnetic field on X axis (body) [uT] (type:float)
-                mag_y                     : Magnetic field on Y axis (body) [uT] (type:float)
-                mag_z                     : Magnetic field on Z axis (body) [uT] (type:float)
-                gps_fix                   : GPS fix (1 = fix, 0 = no fix) (type:uint8_t)
-                gps_lat                   : Latitude [deg] (type:float)
-                gps_lon                   : Longitude [deg] (type:float)
-                gps_alt                   : GPS Altitude [m] (type:float)
-                left_servo_angle          : Left servo motor angle [deg] (type:float)
-                right_servo_angle         : Right servo motor angle [deg] (type:float)
-                nas_n                     : NAS estimated noth position [deg] (type:float)
-                nas_e                     : NAS estimated east position [deg] (type:float)
-                nas_d                     : NAS estimated down position [m] (type:float)
-                nas_vn                    : NAS estimated north velocity [m/s] (type:float)
-                nas_ve                    : NAS estimated east velocity [m/s] (type:float)
-                nas_vd                    : NAS estimated down velocity [m/s] (type:float)
-                nas_qx                    : NAS estimated attitude (qx) [deg] (type:float)
-                nas_qy                    : NAS estimated attitude (qy) [deg] (type:float)
-                nas_qz                    : NAS estimated attitude (qz) [deg] (type:float)
-                nas_qw                    : NAS estimated attitude (qw) [deg] (type:float)
-                nas_bias_x                : NAS gyroscope bias on x axis (type:float)
-                nas_bias_y                : NAS gyroscope bias on y axis (type:float)
-                nas_bias_z                : NAS gyroscope bias on z axis (type:float)
-                wes_n                     : Wind estimated north velocity [m/s] (type:float)
-                wes_e                     : Wind estimated east velocity [m/s] (type:float)
-                pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
-                battery_voltage           : Battery voltage [V] (type:float)
-                cam_battery_voltage        : Camera battery voltage [V] (type:float)
-                cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
-                temperature               : Temperature [degC] (type:float)
-                main_can_status           : Main CAN status (type:uint8_t)
-                motor_can_status          : Motor CAN status (type:uint8_t)
-                rig_can_status            : RIG CAN status (type:uint8_t)
-
-                '''
-                return self.send(self.payload_flight_tm_encode(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, cutter_presence, temperature, main_can_status, motor_can_status, rig_can_status), force_mavlink1=force_mavlink1)
-
-        def rocket_stats_tm_encode(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_bay_max_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state):
-                '''
-                Low Rate Telemetry
-
-                liftoff_ts                : System clock at liftoff [us] (type:uint64_t)
-                liftoff_max_acc_ts        : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
-                liftoff_max_acc           : Maximum liftoff acceleration [m/s2] (type:float)
-                dpl_ts                    : System clock at drouge deployment [us] (type:uint64_t)
-                dpl_max_acc               : Max acceleration during drouge deployment [m/s2] (type:float)
-                max_z_speed_ts            : System clock at ADA max vertical speed [us] (type:uint64_t)
-                max_z_speed               : Max measured vertical speed - ADA [m/s] (type:float)
-                max_airspeed_pitot        : Max speed read by the pitot tube [m/s] (type:float)
-                max_speed_altitude        : Altitude at max speed [m] (type:float)
-                apogee_ts                 : System clock at apogee [us] (type:uint64_t)
-                apogee_lat                : Apogee latitude [deg] (type:float)
-                apogee_lon                : Apogee longitude [deg] (type:float)
-                apogee_alt                : Apogee altitude [m] (type:float)
-                min_pressure              : Apogee pressure - Digital barometer [Pa] (type:float)
-                ada_min_pressure          : Apogee pressure - ADA filtered [Pa] (type:float)
-                dpl_bay_max_pressure        : Max pressure in the deployment bay during drogue deployment [Pa] (type:float)
-                cpu_load                  : CPU load in percentage (type:float)
-                free_heap                 : Amount of available heap in memory (type:uint32_t)
-                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
-                writes_failed             : Number of fwrite() that failed (type:int32_t)
-                hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
-
-                '''
-                return MAVLink_rocket_stats_tm_message(liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_bay_max_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state)
-
-        def rocket_stats_tm_send(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_bay_max_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state, force_mavlink1=False):
-                '''
-                Low Rate Telemetry
-
-                liftoff_ts                : System clock at liftoff [us] (type:uint64_t)
-                liftoff_max_acc_ts        : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
-                liftoff_max_acc           : Maximum liftoff acceleration [m/s2] (type:float)
-                dpl_ts                    : System clock at drouge deployment [us] (type:uint64_t)
-                dpl_max_acc               : Max acceleration during drouge deployment [m/s2] (type:float)
-                max_z_speed_ts            : System clock at ADA max vertical speed [us] (type:uint64_t)
-                max_z_speed               : Max measured vertical speed - ADA [m/s] (type:float)
-                max_airspeed_pitot        : Max speed read by the pitot tube [m/s] (type:float)
-                max_speed_altitude        : Altitude at max speed [m] (type:float)
-                apogee_ts                 : System clock at apogee [us] (type:uint64_t)
-                apogee_lat                : Apogee latitude [deg] (type:float)
-                apogee_lon                : Apogee longitude [deg] (type:float)
-                apogee_alt                : Apogee altitude [m] (type:float)
-                min_pressure              : Apogee pressure - Digital barometer [Pa] (type:float)
-                ada_min_pressure          : Apogee pressure - ADA filtered [Pa] (type:float)
-                dpl_bay_max_pressure        : Max pressure in the deployment bay during drogue deployment [Pa] (type:float)
-                cpu_load                  : CPU load in percentage (type:float)
-                free_heap                 : Amount of available heap in memory (type:uint32_t)
-                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
-                writes_failed             : Number of fwrite() that failed (type:int32_t)
-                hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
-
-                '''
-                return self.send(self.rocket_stats_tm_encode(liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_bay_max_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state), force_mavlink1=force_mavlink1)
-
-        def payload_stats_tm_encode(self, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state):
-                '''
-                Low Rate Telemetry
-
-                liftoff_max_acc_ts        : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
-                liftoff_max_acc           : Maximum liftoff acceleration [m/s2] (type:float)
-                dpl_ts                    : System clock at drouge deployment [us] (type:uint64_t)
-                dpl_max_acc               : Max acceleration during drouge deployment [m/s2] (type:float)
-                max_z_speed_ts            : System clock at max vertical speed [us] (type:uint64_t)
-                max_z_speed               : Max measured vertical speed [m/s] (type:float)
-                max_airspeed_pitot        : Max speed read by the pitot tube [m/s] (type:float)
-                max_speed_altitude        : Altitude at max speed [m] (type:float)
-                apogee_ts                 : System clock at apogee [us] (type:uint64_t)
-                apogee_lat                : Apogee latitude [deg] (type:float)
-                apogee_lon                : Apogee longitude [deg] (type:float)
-                apogee_alt                : Apogee altitude [m] (type:float)
-                min_pressure              : Apogee pressure - Digital barometer [Pa] (type:float)
-                cpu_load                  : CPU load in percentage (type:float)
-                free_heap                 : Amount of available heap in memory (type:uint32_t)
-                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
-                writes_failed             : Number of fwrite() that failed (type:int32_t)
-                hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
-
-                '''
-                return MAVLink_payload_stats_tm_message(liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state)
-
-        def payload_stats_tm_send(self, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state, force_mavlink1=False):
-                '''
-                Low Rate Telemetry
-
-                liftoff_max_acc_ts        : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
-                liftoff_max_acc           : Maximum liftoff acceleration [m/s2] (type:float)
-                dpl_ts                    : System clock at drouge deployment [us] (type:uint64_t)
-                dpl_max_acc               : Max acceleration during drouge deployment [m/s2] (type:float)
-                max_z_speed_ts            : System clock at max vertical speed [us] (type:uint64_t)
-                max_z_speed               : Max measured vertical speed [m/s] (type:float)
-                max_airspeed_pitot        : Max speed read by the pitot tube [m/s] (type:float)
-                max_speed_altitude        : Altitude at max speed [m] (type:float)
-                apogee_ts                 : System clock at apogee [us] (type:uint64_t)
-                apogee_lat                : Apogee latitude [deg] (type:float)
-                apogee_lon                : Apogee longitude [deg] (type:float)
-                apogee_alt                : Apogee altitude [m] (type:float)
-                min_pressure              : Apogee pressure - Digital barometer [Pa] (type:float)
-                cpu_load                  : CPU load in percentage (type:float)
-                free_heap                 : Amount of available heap in memory (type:uint32_t)
-                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
-                writes_failed             : Number of fwrite() that failed (type:int32_t)
-                hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
-
-                '''
-                return self.send(self.payload_stats_tm_encode(liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state), force_mavlink1=force_mavlink1)
-
-        def gse_tm_encode(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_status, payload_board_status, main_can_status, payload_can_status, motor_can_status, log_number, writes_failed):
-                '''
-                Ground Segment Equipment telemetry
-
-                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
-                loadcell_rocket           : Rocket weight [kg] (type:float)
-                loadcell_vessel           : External tank weight [kg] (type:float)
-                filling_pressure          : Refueling line pressure [Bar] (type:float)
-                vessel_pressure           : Vessel tank pressure [Bar] (type:float)
-                filling_valve_state        : 1 If the filling valve is open (type:uint8_t)
-                venting_valve_state        : 1 If the venting valve is open (type:uint8_t)
-                release_valve_state        : 1 If the release valve is open (type:uint8_t)
-                main_valve_state          : 1 If the main valve is open (type:uint8_t)
-                nitrogen_valve_state        : 1 If the nitrogen valve is open (type:uint8_t)
-                gmm_state                 : State of the GroundModeManager (type:uint8_t)
-                tars_state                : State of Tars (type:uint8_t)
-                battery_voltage           : Battery voltage (type:float)
-                current_consumption        : RIG current [A] (type:float)
-                umbilical_current_consumption        : Umbilical current [A] (type:float)
-                main_board_status         : Main board status (1 if armed) (type:uint8_t)
-                payload_board_status        : Payload board status (1 if armed) (type:uint8_t)
-                main_can_status           : Main CAN status (type:uint8_t)
-                payload_can_status        : Payload CAN status (type:uint8_t)
-                motor_can_status          : Motor CAN status (type:uint8_t)
-                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
-                writes_failed             : Number of fwrite() that failed (type:int32_t)
-
-                '''
-                return MAVLink_gse_tm_message(timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_status, payload_board_status, main_can_status, payload_can_status, motor_can_status, log_number, writes_failed)
-
-        def gse_tm_send(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_status, payload_board_status, main_can_status, payload_can_status, motor_can_status, log_number, writes_failed, force_mavlink1=False):
-                '''
-                Ground Segment Equipment telemetry
-
-                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
-                loadcell_rocket           : Rocket weight [kg] (type:float)
-                loadcell_vessel           : External tank weight [kg] (type:float)
-                filling_pressure          : Refueling line pressure [Bar] (type:float)
-                vessel_pressure           : Vessel tank pressure [Bar] (type:float)
-                filling_valve_state        : 1 If the filling valve is open (type:uint8_t)
-                venting_valve_state        : 1 If the venting valve is open (type:uint8_t)
-                release_valve_state        : 1 If the release valve is open (type:uint8_t)
-                main_valve_state          : 1 If the main valve is open (type:uint8_t)
-                nitrogen_valve_state        : 1 If the nitrogen valve is open (type:uint8_t)
-                gmm_state                 : State of the GroundModeManager (type:uint8_t)
-                tars_state                : State of Tars (type:uint8_t)
-                battery_voltage           : Battery voltage (type:float)
-                current_consumption        : RIG current [A] (type:float)
-                umbilical_current_consumption        : Umbilical current [A] (type:float)
-                main_board_status         : Main board status (1 if armed) (type:uint8_t)
-                payload_board_status        : Payload board status (1 if armed) (type:uint8_t)
-                main_can_status           : Main CAN status (type:uint8_t)
-                payload_can_status        : Payload CAN status (type:uint8_t)
-                motor_can_status          : Motor CAN status (type:uint8_t)
-                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
-                writes_failed             : Number of fwrite() that failed (type:int32_t)
-
-                '''
-                return self.send(self.gse_tm_encode(timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_status, payload_board_status, main_can_status, payload_can_status, motor_can_status, log_number, writes_failed), force_mavlink1=force_mavlink1)
-
-        def motor_tm_encode(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, writes_failed, hil_state):
-                '''
-                Motor rocket telemetry
-
-                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
-                top_tank_pressure         : Tank upper pressure [Bar] (type:float)
-                bottom_tank_pressure        : Tank bottom pressure [Bar] (type:float)
-                combustion_chamber_pressure        : Pressure inside the combustion chamber used for automatic shutdown [Bar] (type:float)
-                tank_temperature          : Tank temperature (type:float)
-                main_valve_state          : 1 If the main valve is open (type:uint8_t)
-                venting_valve_state        : 1 If the venting valve is open (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)
-                writes_failed             : Number of fwrite() that failed (type:int32_t)
-                hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
-
-                '''
-                return MAVLink_motor_tm_message(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, writes_failed, hil_state)
-
-        def motor_tm_send(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, writes_failed, hil_state, force_mavlink1=False):
-                '''
-                Motor rocket telemetry
-
-                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
-                top_tank_pressure         : Tank upper pressure [Bar] (type:float)
-                bottom_tank_pressure        : Tank bottom pressure [Bar] (type:float)
-                combustion_chamber_pressure        : Pressure inside the combustion chamber used for automatic shutdown [Bar] (type:float)
-                tank_temperature          : Tank temperature (type:float)
-                main_valve_state          : 1 If the main valve is open (type:uint8_t)
-                venting_valve_state        : 1 If the venting valve is open (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)
-                writes_failed             : Number of fwrite() that failed (type:int32_t)
-                hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
-
-                '''
-                return self.send(self.motor_tm_encode(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, writes_failed, hil_state), force_mavlink1=force_mavlink1)
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        state                     : ADA current state (type:uint8_t)
+        kalman_x0                 : Kalman state variable 0 (pressure) (type:float)
+        kalman_x1                 : Kalman state variable 1 (pressure velocity) (type:float)
+        kalman_x2                 : Kalman state variable 2 (pressure acceleration) (type:float)
+        vertical_speed            : Vertical speed computed by the ADA [m/s] (type:float)
+        msl_altitude              : Altitude w.r.t. mean sea level [m] (type:float)
+        ref_pressure              : Calibration pressure [Pa] (type:float)
+        ref_altitude              : Calibration altitude [m] (type:float)
+        ref_temperature           : Calibration temperature [degC] (type:float)
+        msl_pressure              : Expected pressure at mean sea level [Pa] (type:float)
+        msl_temperature           : Expected temperature at mean sea level [degC] (type:float)
+        dpl_altitude              : Main parachute deployment altituyde [m] (type:float)
+
+        """
+        self.send(self.ada_tm_encode(timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude), force_mavlink1=force_mavlink1)
+
+    def nas_tm_encode(self, timestamp: int, state: int, nas_n: float, nas_e: float, nas_d: float, nas_vn: float, nas_ve: float, nas_vd: float, nas_qx: float, nas_qy: float, nas_qz: float, nas_qw: float, nas_bias_x: float, nas_bias_y: float, nas_bias_z: float, ref_pressure: float, ref_temperature: float, ref_latitude: float, ref_longitude: float) -> MAVLink_nas_tm_message:
+        """
+        Navigation System status telemetry
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        state                     : NAS current state (type:uint8_t)
+        nas_n                     : Navigation system estimated noth position [deg] (type:float)
+        nas_e                     : Navigation system estimated east position [deg] (type:float)
+        nas_d                     : Navigation system estimated down position [m] (type:float)
+        nas_vn                    : Navigation system estimated north velocity [m/s] (type:float)
+        nas_ve                    : Navigation system estimated east velocity [m/s] (type:float)
+        nas_vd                    : Navigation system estimated down velocity [m/s] (type:float)
+        nas_qx                    : Navigation system estimated attitude (qx) [deg] (type:float)
+        nas_qy                    : Navigation system estimated attitude (qy) [deg] (type:float)
+        nas_qz                    : Navigation system estimated attitude (qz) [deg] (type:float)
+        nas_qw                    : Navigation system estimated attitude (qw) [deg] (type:float)
+        nas_bias_x                : Navigation system gyroscope bias on x axis (type:float)
+        nas_bias_y                : Navigation system gyroscope bias on y axis (type:float)
+        nas_bias_z                : Navigation system gyroscope bias on z axis (type:float)
+        ref_pressure              : Calibration pressure [Pa] (type:float)
+        ref_temperature           : Calibration temperature [degC] (type:float)
+        ref_latitude              : Calibration latitude [deg] (type:float)
+        ref_longitude             : Calibration longitude [deg] (type:float)
+
+        """
+        return MAVLink_nas_tm_message(timestamp, state, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, ref_pressure, ref_temperature, ref_latitude, ref_longitude)
+
+    def nas_tm_send(self, timestamp: int, state: int, nas_n: float, nas_e: float, nas_d: float, nas_vn: float, nas_ve: float, nas_vd: float, nas_qx: float, nas_qy: float, nas_qz: float, nas_qw: float, nas_bias_x: float, nas_bias_y: float, nas_bias_z: float, ref_pressure: float, ref_temperature: float, ref_latitude: float, ref_longitude: float, force_mavlink1: bool = False) -> None:
+        """
+        Navigation System status telemetry
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        state                     : NAS current state (type:uint8_t)
+        nas_n                     : Navigation system estimated noth position [deg] (type:float)
+        nas_e                     : Navigation system estimated east position [deg] (type:float)
+        nas_d                     : Navigation system estimated down position [m] (type:float)
+        nas_vn                    : Navigation system estimated north velocity [m/s] (type:float)
+        nas_ve                    : Navigation system estimated east velocity [m/s] (type:float)
+        nas_vd                    : Navigation system estimated down velocity [m/s] (type:float)
+        nas_qx                    : Navigation system estimated attitude (qx) [deg] (type:float)
+        nas_qy                    : Navigation system estimated attitude (qy) [deg] (type:float)
+        nas_qz                    : Navigation system estimated attitude (qz) [deg] (type:float)
+        nas_qw                    : Navigation system estimated attitude (qw) [deg] (type:float)
+        nas_bias_x                : Navigation system gyroscope bias on x axis (type:float)
+        nas_bias_y                : Navigation system gyroscope bias on y axis (type:float)
+        nas_bias_z                : Navigation system gyroscope bias on z axis (type:float)
+        ref_pressure              : Calibration pressure [Pa] (type:float)
+        ref_temperature           : Calibration temperature [degC] (type:float)
+        ref_latitude              : Calibration latitude [deg] (type:float)
+        ref_longitude             : Calibration longitude [deg] (type:float)
+
+        """
+        self.send(self.nas_tm_encode(timestamp, state, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, ref_pressure, ref_temperature, ref_latitude, ref_longitude), force_mavlink1=force_mavlink1)
+
+    def mea_tm_encode(self, timestamp: int, state: int, kalman_x0: float, kalman_x1: float, kalman_x2: float, mass: float, corrected_pressure: float) -> MAVLink_mea_tm_message:
+        """
+        Mass Estimation Algorithm status telemetry
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        state                     : MEA current state (type:uint8_t)
+        kalman_x0                 : Kalman state variable 0 (corrected pressure) (type:float)
+        kalman_x1                 : Kalman state variable 1 (type:float)
+        kalman_x2                 : Kalman state variable 2 (mass) (type:float)
+        mass                      : Mass estimated [kg] (type:float)
+        corrected_pressure        : Corrected pressure [Pa] (type:float)
+
+        """
+        return MAVLink_mea_tm_message(timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure)
+
+    def mea_tm_send(self, timestamp: int, state: int, kalman_x0: float, kalman_x1: float, kalman_x2: float, mass: float, corrected_pressure: float, force_mavlink1: bool = False) -> None:
+        """
+        Mass Estimation Algorithm status telemetry
+
+        timestamp                 : When was this logged [us] (type:uint64_t)
+        state                     : MEA current state (type:uint8_t)
+        kalman_x0                 : Kalman state variable 0 (corrected pressure) (type:float)
+        kalman_x1                 : Kalman state variable 1 (type:float)
+        kalman_x2                 : Kalman state variable 2 (mass) (type:float)
+        mass                      : Mass estimated [kg] (type:float)
+        corrected_pressure        : Corrected pressure [Pa] (type:float)
+
+        """
+        self.send(self.mea_tm_encode(timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure), force_mavlink1=force_mavlink1)
+
+    def rocket_flight_tm_encode(self, timestamp: int, ada_state: int, fmm_state: int, dpl_state: int, abk_state: int, nas_state: int, mea_state: int, pressure_ada: float, pressure_digi: float, pressure_static: float, pressure_dpl: float, airspeed_pitot: float, altitude_agl: float, ada_vert_speed: float, mea_mass: float, acc_x: float, acc_y: float, acc_z: float, gyro_x: float, gyro_y: float, gyro_z: float, mag_x: float, mag_y: float, mag_z: float, gps_fix: int, gps_lat: float, gps_lon: float, gps_alt: float, abk_angle: float, nas_n: float, nas_e: float, nas_d: float, nas_vn: float, nas_ve: float, nas_vd: float, nas_qx: float, nas_qy: float, nas_qz: float, nas_qw: float, nas_bias_x: float, nas_bias_y: float, nas_bias_z: float, pin_launch: int, pin_nosecone: int, pin_expulsion: int, cutter_presence: int, battery_voltage: float, cam_battery_voltage: float, temperature: float, payload_can_status: int, motor_can_status: int, rig_can_status: int) -> MAVLink_rocket_flight_tm_message:
+        """
+        High Rate Telemetry
+
+        timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
+        ada_state                 : ADA Controller State (type:uint8_t)
+        fmm_state                 : Flight Mode Manager State (type:uint8_t)
+        dpl_state                 : Deployment Controller State (type:uint8_t)
+        abk_state                 : Airbrake FSM state (type:uint8_t)
+        nas_state                 : NAS FSM State (type:uint8_t)
+        mea_state                 : MEA Controller State (type:uint8_t)
+        pressure_ada              : Atmospheric pressure estimated by ADA [Pa] (type:float)
+        pressure_digi             : Pressure from digital sensor [Pa] (type:float)
+        pressure_static           : Pressure from static port [Pa] (type:float)
+        pressure_dpl              : Pressure from deployment vane sensor [Pa] (type:float)
+        airspeed_pitot            : Pitot airspeed [m/s] (type:float)
+        altitude_agl              : Altitude above ground level [m] (type:float)
+        ada_vert_speed            : Vertical speed estimated by ADA [m/s] (type:float)
+        mea_mass                  : Mass estimated by MEA [kg] (type:float)
+        acc_x                     : Acceleration on X axis (body) [m/s^2] (type:float)
+        acc_y                     : Acceleration on Y axis (body) [m/s^2] (type:float)
+        acc_z                     : Acceleration on Z axis (body) [m/s^2] (type:float)
+        gyro_x                    : Angular speed on X axis (body) [rad/s] (type:float)
+        gyro_y                    : Angular speed on Y axis (body) [rad/s] (type:float)
+        gyro_z                    : Angular speed on Z axis (body) [rad/s] (type:float)
+        mag_x                     : Magnetic field on X axis (body) [uT] (type:float)
+        mag_y                     : Magnetic field on Y axis (body) [uT] (type:float)
+        mag_z                     : Magnetic field on Z axis (body) [uT] (type:float)
+        gps_fix                   : GPS fix (1 = fix, 0 = no fix) (type:uint8_t)
+        gps_lat                   : Latitude [deg] (type:float)
+        gps_lon                   : Longitude [deg] (type:float)
+        gps_alt                   : GPS Altitude [m] (type:float)
+        abk_angle                 : Air Brakes angle [deg] (type:float)
+        nas_n                     : NAS estimated noth position [deg] (type:float)
+        nas_e                     : NAS estimated east position [deg] (type:float)
+        nas_d                     : NAS estimated down position [m] (type:float)
+        nas_vn                    : NAS estimated north velocity [m/s] (type:float)
+        nas_ve                    : NAS estimated east velocity [m/s] (type:float)
+        nas_vd                    : NAS estimated down velocity [m/s] (type:float)
+        nas_qx                    : NAS estimated attitude (qx) [deg] (type:float)
+        nas_qy                    : NAS estimated attitude (qy) [deg] (type:float)
+        nas_qz                    : NAS estimated attitude (qz) [deg] (type:float)
+        nas_qw                    : NAS estimated attitude (qw) [deg] (type:float)
+        nas_bias_x                : NAS gyroscope bias on x axis (type:float)
+        nas_bias_y                : NAS gyroscope bias on y axis (type:float)
+        nas_bias_z                : NAS gyroscope bias on z axis (type:float)
+        pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
+        pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
+        pin_expulsion             : Servo sensor status (1 = actuated, 0 = idle) (type:uint8_t)
+        cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
+        battery_voltage           : Battery voltage [V] (type:float)
+        cam_battery_voltage        : Camera battery voltage [V] (type:float)
+        temperature               : Temperature [degC] (type:float)
+        payload_can_status        : Payload CAN status (type:uint8_t)
+        motor_can_status          : Motor CAN status (type:uint8_t)
+        rig_can_status            : RIG CAN status (type:uint8_t)
+
+        """
+        return MAVLink_rocket_flight_tm_message(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, temperature, payload_can_status, motor_can_status, rig_can_status)
+
+    def rocket_flight_tm_send(self, timestamp: int, ada_state: int, fmm_state: int, dpl_state: int, abk_state: int, nas_state: int, mea_state: int, pressure_ada: float, pressure_digi: float, pressure_static: float, pressure_dpl: float, airspeed_pitot: float, altitude_agl: float, ada_vert_speed: float, mea_mass: float, acc_x: float, acc_y: float, acc_z: float, gyro_x: float, gyro_y: float, gyro_z: float, mag_x: float, mag_y: float, mag_z: float, gps_fix: int, gps_lat: float, gps_lon: float, gps_alt: float, abk_angle: float, nas_n: float, nas_e: float, nas_d: float, nas_vn: float, nas_ve: float, nas_vd: float, nas_qx: float, nas_qy: float, nas_qz: float, nas_qw: float, nas_bias_x: float, nas_bias_y: float, nas_bias_z: float, pin_launch: int, pin_nosecone: int, pin_expulsion: int, cutter_presence: int, battery_voltage: float, cam_battery_voltage: float, temperature: float, payload_can_status: int, motor_can_status: int, rig_can_status: int, force_mavlink1: bool = False) -> None:
+        """
+        High Rate Telemetry
+
+        timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
+        ada_state                 : ADA Controller State (type:uint8_t)
+        fmm_state                 : Flight Mode Manager State (type:uint8_t)
+        dpl_state                 : Deployment Controller State (type:uint8_t)
+        abk_state                 : Airbrake FSM state (type:uint8_t)
+        nas_state                 : NAS FSM State (type:uint8_t)
+        mea_state                 : MEA Controller State (type:uint8_t)
+        pressure_ada              : Atmospheric pressure estimated by ADA [Pa] (type:float)
+        pressure_digi             : Pressure from digital sensor [Pa] (type:float)
+        pressure_static           : Pressure from static port [Pa] (type:float)
+        pressure_dpl              : Pressure from deployment vane sensor [Pa] (type:float)
+        airspeed_pitot            : Pitot airspeed [m/s] (type:float)
+        altitude_agl              : Altitude above ground level [m] (type:float)
+        ada_vert_speed            : Vertical speed estimated by ADA [m/s] (type:float)
+        mea_mass                  : Mass estimated by MEA [kg] (type:float)
+        acc_x                     : Acceleration on X axis (body) [m/s^2] (type:float)
+        acc_y                     : Acceleration on Y axis (body) [m/s^2] (type:float)
+        acc_z                     : Acceleration on Z axis (body) [m/s^2] (type:float)
+        gyro_x                    : Angular speed on X axis (body) [rad/s] (type:float)
+        gyro_y                    : Angular speed on Y axis (body) [rad/s] (type:float)
+        gyro_z                    : Angular speed on Z axis (body) [rad/s] (type:float)
+        mag_x                     : Magnetic field on X axis (body) [uT] (type:float)
+        mag_y                     : Magnetic field on Y axis (body) [uT] (type:float)
+        mag_z                     : Magnetic field on Z axis (body) [uT] (type:float)
+        gps_fix                   : GPS fix (1 = fix, 0 = no fix) (type:uint8_t)
+        gps_lat                   : Latitude [deg] (type:float)
+        gps_lon                   : Longitude [deg] (type:float)
+        gps_alt                   : GPS Altitude [m] (type:float)
+        abk_angle                 : Air Brakes angle [deg] (type:float)
+        nas_n                     : NAS estimated noth position [deg] (type:float)
+        nas_e                     : NAS estimated east position [deg] (type:float)
+        nas_d                     : NAS estimated down position [m] (type:float)
+        nas_vn                    : NAS estimated north velocity [m/s] (type:float)
+        nas_ve                    : NAS estimated east velocity [m/s] (type:float)
+        nas_vd                    : NAS estimated down velocity [m/s] (type:float)
+        nas_qx                    : NAS estimated attitude (qx) [deg] (type:float)
+        nas_qy                    : NAS estimated attitude (qy) [deg] (type:float)
+        nas_qz                    : NAS estimated attitude (qz) [deg] (type:float)
+        nas_qw                    : NAS estimated attitude (qw) [deg] (type:float)
+        nas_bias_x                : NAS gyroscope bias on x axis (type:float)
+        nas_bias_y                : NAS gyroscope bias on y axis (type:float)
+        nas_bias_z                : NAS gyroscope bias on z axis (type:float)
+        pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
+        pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
+        pin_expulsion             : Servo sensor status (1 = actuated, 0 = idle) (type:uint8_t)
+        cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
+        battery_voltage           : Battery voltage [V] (type:float)
+        cam_battery_voltage        : Camera battery voltage [V] (type:float)
+        temperature               : Temperature [degC] (type:float)
+        payload_can_status        : Payload CAN status (type:uint8_t)
+        motor_can_status          : Motor CAN status (type:uint8_t)
+        rig_can_status            : RIG CAN status (type:uint8_t)
+
+        """
+        self.send(self.rocket_flight_tm_encode(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, temperature, payload_can_status, motor_can_status, rig_can_status), force_mavlink1=force_mavlink1)
+
+    def payload_flight_tm_encode(self, timestamp: int, fmm_state: int, nas_state: int, wes_state: int, pressure_digi: float, pressure_static: float, airspeed_pitot: float, altitude_agl: float, acc_x: float, acc_y: float, acc_z: float, gyro_x: float, gyro_y: float, gyro_z: float, mag_x: float, mag_y: float, mag_z: float, gps_fix: int, gps_lat: float, gps_lon: float, gps_alt: float, left_servo_angle: float, right_servo_angle: float, nas_n: float, nas_e: float, nas_d: float, nas_vn: float, nas_ve: float, nas_vd: float, nas_qx: float, nas_qy: float, nas_qz: float, nas_qw: float, nas_bias_x: float, nas_bias_y: float, nas_bias_z: float, wes_n: float, wes_e: float, pin_nosecone: int, battery_voltage: float, cam_battery_voltage: float, cutter_presence: int, temperature: float, main_can_status: int, motor_can_status: int, rig_can_status: int) -> MAVLink_payload_flight_tm_message:
+        """
+        High Rate Telemetry
+
+        timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
+        fmm_state                 : Flight Mode Manager State (type:uint8_t)
+        nas_state                 : NAS FSM State (type:uint8_t)
+        wes_state                 : Wind Estimation System FSM State (type:uint8_t)
+        pressure_digi             : Pressure from digital sensor [Pa] (type:float)
+        pressure_static           : Pressure from static port [Pa] (type:float)
+        airspeed_pitot            : Pitot airspeed [m/s] (type:float)
+        altitude_agl              : Altitude above ground level [m] (type:float)
+        acc_x                     : Acceleration on X axis (body) [m/s^2] (type:float)
+        acc_y                     : Acceleration on Y axis (body) [m/s^2] (type:float)
+        acc_z                     : Acceleration on Z axis (body) [m/s^2] (type:float)
+        gyro_x                    : Angular speed on X axis (body) [rad/s] (type:float)
+        gyro_y                    : Angular speed on Y axis (body) [rad/s] (type:float)
+        gyro_z                    : Angular speed on Z axis (body) [rad/s] (type:float)
+        mag_x                     : Magnetic field on X axis (body) [uT] (type:float)
+        mag_y                     : Magnetic field on Y axis (body) [uT] (type:float)
+        mag_z                     : Magnetic field on Z axis (body) [uT] (type:float)
+        gps_fix                   : GPS fix (1 = fix, 0 = no fix) (type:uint8_t)
+        gps_lat                   : Latitude [deg] (type:float)
+        gps_lon                   : Longitude [deg] (type:float)
+        gps_alt                   : GPS Altitude [m] (type:float)
+        left_servo_angle          : Left servo motor angle [deg] (type:float)
+        right_servo_angle         : Right servo motor angle [deg] (type:float)
+        nas_n                     : NAS estimated noth position [deg] (type:float)
+        nas_e                     : NAS estimated east position [deg] (type:float)
+        nas_d                     : NAS estimated down position [m] (type:float)
+        nas_vn                    : NAS estimated north velocity [m/s] (type:float)
+        nas_ve                    : NAS estimated east velocity [m/s] (type:float)
+        nas_vd                    : NAS estimated down velocity [m/s] (type:float)
+        nas_qx                    : NAS estimated attitude (qx) [deg] (type:float)
+        nas_qy                    : NAS estimated attitude (qy) [deg] (type:float)
+        nas_qz                    : NAS estimated attitude (qz) [deg] (type:float)
+        nas_qw                    : NAS estimated attitude (qw) [deg] (type:float)
+        nas_bias_x                : NAS gyroscope bias on x axis (type:float)
+        nas_bias_y                : NAS gyroscope bias on y axis (type:float)
+        nas_bias_z                : NAS gyroscope bias on z axis (type:float)
+        wes_n                     : Wind estimated north velocity [m/s] (type:float)
+        wes_e                     : Wind estimated east velocity [m/s] (type:float)
+        pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
+        battery_voltage           : Battery voltage [V] (type:float)
+        cam_battery_voltage        : Camera battery voltage [V] (type:float)
+        cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
+        temperature               : Temperature [degC] (type:float)
+        main_can_status           : Main CAN status (type:uint8_t)
+        motor_can_status          : Motor CAN status (type:uint8_t)
+        rig_can_status            : RIG CAN status (type:uint8_t)
+
+        """
+        return MAVLink_payload_flight_tm_message(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, cutter_presence, temperature, main_can_status, motor_can_status, rig_can_status)
+
+    def payload_flight_tm_send(self, timestamp: int, fmm_state: int, nas_state: int, wes_state: int, pressure_digi: float, pressure_static: float, airspeed_pitot: float, altitude_agl: float, acc_x: float, acc_y: float, acc_z: float, gyro_x: float, gyro_y: float, gyro_z: float, mag_x: float, mag_y: float, mag_z: float, gps_fix: int, gps_lat: float, gps_lon: float, gps_alt: float, left_servo_angle: float, right_servo_angle: float, nas_n: float, nas_e: float, nas_d: float, nas_vn: float, nas_ve: float, nas_vd: float, nas_qx: float, nas_qy: float, nas_qz: float, nas_qw: float, nas_bias_x: float, nas_bias_y: float, nas_bias_z: float, wes_n: float, wes_e: float, pin_nosecone: int, battery_voltage: float, cam_battery_voltage: float, cutter_presence: int, temperature: float, main_can_status: int, motor_can_status: int, rig_can_status: int, force_mavlink1: bool = False) -> None:
+        """
+        High Rate Telemetry
+
+        timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
+        fmm_state                 : Flight Mode Manager State (type:uint8_t)
+        nas_state                 : NAS FSM State (type:uint8_t)
+        wes_state                 : Wind Estimation System FSM State (type:uint8_t)
+        pressure_digi             : Pressure from digital sensor [Pa] (type:float)
+        pressure_static           : Pressure from static port [Pa] (type:float)
+        airspeed_pitot            : Pitot airspeed [m/s] (type:float)
+        altitude_agl              : Altitude above ground level [m] (type:float)
+        acc_x                     : Acceleration on X axis (body) [m/s^2] (type:float)
+        acc_y                     : Acceleration on Y axis (body) [m/s^2] (type:float)
+        acc_z                     : Acceleration on Z axis (body) [m/s^2] (type:float)
+        gyro_x                    : Angular speed on X axis (body) [rad/s] (type:float)
+        gyro_y                    : Angular speed on Y axis (body) [rad/s] (type:float)
+        gyro_z                    : Angular speed on Z axis (body) [rad/s] (type:float)
+        mag_x                     : Magnetic field on X axis (body) [uT] (type:float)
+        mag_y                     : Magnetic field on Y axis (body) [uT] (type:float)
+        mag_z                     : Magnetic field on Z axis (body) [uT] (type:float)
+        gps_fix                   : GPS fix (1 = fix, 0 = no fix) (type:uint8_t)
+        gps_lat                   : Latitude [deg] (type:float)
+        gps_lon                   : Longitude [deg] (type:float)
+        gps_alt                   : GPS Altitude [m] (type:float)
+        left_servo_angle          : Left servo motor angle [deg] (type:float)
+        right_servo_angle         : Right servo motor angle [deg] (type:float)
+        nas_n                     : NAS estimated noth position [deg] (type:float)
+        nas_e                     : NAS estimated east position [deg] (type:float)
+        nas_d                     : NAS estimated down position [m] (type:float)
+        nas_vn                    : NAS estimated north velocity [m/s] (type:float)
+        nas_ve                    : NAS estimated east velocity [m/s] (type:float)
+        nas_vd                    : NAS estimated down velocity [m/s] (type:float)
+        nas_qx                    : NAS estimated attitude (qx) [deg] (type:float)
+        nas_qy                    : NAS estimated attitude (qy) [deg] (type:float)
+        nas_qz                    : NAS estimated attitude (qz) [deg] (type:float)
+        nas_qw                    : NAS estimated attitude (qw) [deg] (type:float)
+        nas_bias_x                : NAS gyroscope bias on x axis (type:float)
+        nas_bias_y                : NAS gyroscope bias on y axis (type:float)
+        nas_bias_z                : NAS gyroscope bias on z axis (type:float)
+        wes_n                     : Wind estimated north velocity [m/s] (type:float)
+        wes_e                     : Wind estimated east velocity [m/s] (type:float)
+        pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
+        battery_voltage           : Battery voltage [V] (type:float)
+        cam_battery_voltage        : Camera battery voltage [V] (type:float)
+        cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
+        temperature               : Temperature [degC] (type:float)
+        main_can_status           : Main CAN status (type:uint8_t)
+        motor_can_status          : Motor CAN status (type:uint8_t)
+        rig_can_status            : RIG CAN status (type:uint8_t)
+
+        """
+        self.send(self.payload_flight_tm_encode(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, cutter_presence, temperature, main_can_status, motor_can_status, rig_can_status), force_mavlink1=force_mavlink1)
+
+    def rocket_stats_tm_encode(self, liftoff_ts: int, liftoff_max_acc_ts: int, liftoff_max_acc: float, dpl_ts: int, dpl_max_acc: float, max_z_speed_ts: int, max_z_speed: float, max_airspeed_pitot: float, max_speed_altitude: float, apogee_ts: int, apogee_lat: float, apogee_lon: float, apogee_alt: float, min_pressure: float, ada_min_pressure: float, dpl_bay_max_pressure: float, cpu_load: float, free_heap: int, log_number: int, writes_failed: int, hil_state: int) -> MAVLink_rocket_stats_tm_message:
+        """
+        Low Rate Telemetry
+
+        liftoff_ts                : System clock at liftoff [us] (type:uint64_t)
+        liftoff_max_acc_ts        : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
+        liftoff_max_acc           : Maximum liftoff acceleration [m/s2] (type:float)
+        dpl_ts                    : System clock at drouge deployment [us] (type:uint64_t)
+        dpl_max_acc               : Max acceleration during drouge deployment [m/s2] (type:float)
+        max_z_speed_ts            : System clock at ADA max vertical speed [us] (type:uint64_t)
+        max_z_speed               : Max measured vertical speed - ADA [m/s] (type:float)
+        max_airspeed_pitot        : Max speed read by the pitot tube [m/s] (type:float)
+        max_speed_altitude        : Altitude at max speed [m] (type:float)
+        apogee_ts                 : System clock at apogee [us] (type:uint64_t)
+        apogee_lat                : Apogee latitude [deg] (type:float)
+        apogee_lon                : Apogee longitude [deg] (type:float)
+        apogee_alt                : Apogee altitude [m] (type:float)
+        min_pressure              : Apogee pressure - Digital barometer [Pa] (type:float)
+        ada_min_pressure          : Apogee pressure - ADA filtered [Pa] (type:float)
+        dpl_bay_max_pressure        : Max pressure in the deployment bay during drogue deployment [Pa] (type:float)
+        cpu_load                  : CPU load in percentage (type:float)
+        free_heap                 : Amount of available heap in memory (type:uint32_t)
+        log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+        writes_failed             : Number of fwrite() that failed (type:int32_t)
+        hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
+
+        """
+        return MAVLink_rocket_stats_tm_message(liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_bay_max_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state)
+
+    def rocket_stats_tm_send(self, liftoff_ts: int, liftoff_max_acc_ts: int, liftoff_max_acc: float, dpl_ts: int, dpl_max_acc: float, max_z_speed_ts: int, max_z_speed: float, max_airspeed_pitot: float, max_speed_altitude: float, apogee_ts: int, apogee_lat: float, apogee_lon: float, apogee_alt: float, min_pressure: float, ada_min_pressure: float, dpl_bay_max_pressure: float, cpu_load: float, free_heap: int, log_number: int, writes_failed: int, hil_state: int, force_mavlink1: bool = False) -> None:
+        """
+        Low Rate Telemetry
+
+        liftoff_ts                : System clock at liftoff [us] (type:uint64_t)
+        liftoff_max_acc_ts        : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
+        liftoff_max_acc           : Maximum liftoff acceleration [m/s2] (type:float)
+        dpl_ts                    : System clock at drouge deployment [us] (type:uint64_t)
+        dpl_max_acc               : Max acceleration during drouge deployment [m/s2] (type:float)
+        max_z_speed_ts            : System clock at ADA max vertical speed [us] (type:uint64_t)
+        max_z_speed               : Max measured vertical speed - ADA [m/s] (type:float)
+        max_airspeed_pitot        : Max speed read by the pitot tube [m/s] (type:float)
+        max_speed_altitude        : Altitude at max speed [m] (type:float)
+        apogee_ts                 : System clock at apogee [us] (type:uint64_t)
+        apogee_lat                : Apogee latitude [deg] (type:float)
+        apogee_lon                : Apogee longitude [deg] (type:float)
+        apogee_alt                : Apogee altitude [m] (type:float)
+        min_pressure              : Apogee pressure - Digital barometer [Pa] (type:float)
+        ada_min_pressure          : Apogee pressure - ADA filtered [Pa] (type:float)
+        dpl_bay_max_pressure        : Max pressure in the deployment bay during drogue deployment [Pa] (type:float)
+        cpu_load                  : CPU load in percentage (type:float)
+        free_heap                 : Amount of available heap in memory (type:uint32_t)
+        log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+        writes_failed             : Number of fwrite() that failed (type:int32_t)
+        hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
+
+        """
+        self.send(self.rocket_stats_tm_encode(liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_bay_max_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state), force_mavlink1=force_mavlink1)
+
+    def payload_stats_tm_encode(self, liftoff_max_acc_ts: int, liftoff_max_acc: float, dpl_ts: int, dpl_max_acc: float, max_z_speed_ts: int, max_z_speed: float, max_airspeed_pitot: float, max_speed_altitude: float, apogee_ts: int, apogee_lat: float, apogee_lon: float, apogee_alt: float, min_pressure: float, cpu_load: float, free_heap: int, log_number: int, writes_failed: int, hil_state: int) -> MAVLink_payload_stats_tm_message:
+        """
+        Low Rate Telemetry
+
+        liftoff_max_acc_ts        : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
+        liftoff_max_acc           : Maximum liftoff acceleration [m/s2] (type:float)
+        dpl_ts                    : System clock at drouge deployment [us] (type:uint64_t)
+        dpl_max_acc               : Max acceleration during drouge deployment [m/s2] (type:float)
+        max_z_speed_ts            : System clock at max vertical speed [us] (type:uint64_t)
+        max_z_speed               : Max measured vertical speed [m/s] (type:float)
+        max_airspeed_pitot        : Max speed read by the pitot tube [m/s] (type:float)
+        max_speed_altitude        : Altitude at max speed [m] (type:float)
+        apogee_ts                 : System clock at apogee [us] (type:uint64_t)
+        apogee_lat                : Apogee latitude [deg] (type:float)
+        apogee_lon                : Apogee longitude [deg] (type:float)
+        apogee_alt                : Apogee altitude [m] (type:float)
+        min_pressure              : Apogee pressure - Digital barometer [Pa] (type:float)
+        cpu_load                  : CPU load in percentage (type:float)
+        free_heap                 : Amount of available heap in memory (type:uint32_t)
+        log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+        writes_failed             : Number of fwrite() that failed (type:int32_t)
+        hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
+
+        """
+        return MAVLink_payload_stats_tm_message(liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state)
+
+    def payload_stats_tm_send(self, liftoff_max_acc_ts: int, liftoff_max_acc: float, dpl_ts: int, dpl_max_acc: float, max_z_speed_ts: int, max_z_speed: float, max_airspeed_pitot: float, max_speed_altitude: float, apogee_ts: int, apogee_lat: float, apogee_lon: float, apogee_alt: float, min_pressure: float, cpu_load: float, free_heap: int, log_number: int, writes_failed: int, hil_state: int, force_mavlink1: bool = False) -> None:
+        """
+        Low Rate Telemetry
+
+        liftoff_max_acc_ts        : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
+        liftoff_max_acc           : Maximum liftoff acceleration [m/s2] (type:float)
+        dpl_ts                    : System clock at drouge deployment [us] (type:uint64_t)
+        dpl_max_acc               : Max acceleration during drouge deployment [m/s2] (type:float)
+        max_z_speed_ts            : System clock at max vertical speed [us] (type:uint64_t)
+        max_z_speed               : Max measured vertical speed [m/s] (type:float)
+        max_airspeed_pitot        : Max speed read by the pitot tube [m/s] (type:float)
+        max_speed_altitude        : Altitude at max speed [m] (type:float)
+        apogee_ts                 : System clock at apogee [us] (type:uint64_t)
+        apogee_lat                : Apogee latitude [deg] (type:float)
+        apogee_lon                : Apogee longitude [deg] (type:float)
+        apogee_alt                : Apogee altitude [m] (type:float)
+        min_pressure              : Apogee pressure - Digital barometer [Pa] (type:float)
+        cpu_load                  : CPU load in percentage (type:float)
+        free_heap                 : Amount of available heap in memory (type:uint32_t)
+        log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+        writes_failed             : Number of fwrite() that failed (type:int32_t)
+        hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
+
+        """
+        self.send(self.payload_stats_tm_encode(liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, log_number, writes_failed, hil_state), force_mavlink1=force_mavlink1)
+
+    def gse_tm_encode(self, timestamp: int, loadcell_rocket: float, loadcell_vessel: float, filling_pressure: float, vessel_pressure: float, filling_valve_state: int, venting_valve_state: int, release_valve_state: int, main_valve_state: int, nitrogen_valve_state: int, gmm_state: int, tars_state: int, battery_voltage: float, current_consumption: float, umbilical_current_consumption: float, main_board_status: int, payload_board_status: int, main_can_status: int, payload_can_status: int, motor_can_status: int, log_number: int, writes_failed: int) -> MAVLink_gse_tm_message:
+        """
+        Ground Segment Equipment telemetry
+
+        timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
+        loadcell_rocket           : Rocket weight [kg] (type:float)
+        loadcell_vessel           : External tank weight [kg] (type:float)
+        filling_pressure          : Refueling line pressure [Bar] (type:float)
+        vessel_pressure           : Vessel tank pressure [Bar] (type:float)
+        filling_valve_state        : 1 If the filling valve is open (type:uint8_t)
+        venting_valve_state        : 1 If the venting valve is open (type:uint8_t)
+        release_valve_state        : 1 If the release valve is open (type:uint8_t)
+        main_valve_state          : 1 If the main valve is open (type:uint8_t)
+        nitrogen_valve_state        : 1 If the nitrogen valve is open (type:uint8_t)
+        gmm_state                 : State of the GroundModeManager (type:uint8_t)
+        tars_state                : State of Tars (type:uint8_t)
+        battery_voltage           : Battery voltage (type:float)
+        current_consumption        : RIG current [A] (type:float)
+        umbilical_current_consumption        : Umbilical current [A] (type:float)
+        main_board_status         : Main board status (1 if armed) (type:uint8_t)
+        payload_board_status        : Payload board status (1 if armed) (type:uint8_t)
+        main_can_status           : Main CAN status (type:uint8_t)
+        payload_can_status        : Payload CAN status (type:uint8_t)
+        motor_can_status          : Motor CAN status (type:uint8_t)
+        log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+        writes_failed             : Number of fwrite() that failed (type:int32_t)
+
+        """
+        return MAVLink_gse_tm_message(timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_status, payload_board_status, main_can_status, payload_can_status, motor_can_status, log_number, writes_failed)
+
+    def gse_tm_send(self, timestamp: int, loadcell_rocket: float, loadcell_vessel: float, filling_pressure: float, vessel_pressure: float, filling_valve_state: int, venting_valve_state: int, release_valve_state: int, main_valve_state: int, nitrogen_valve_state: int, gmm_state: int, tars_state: int, battery_voltage: float, current_consumption: float, umbilical_current_consumption: float, main_board_status: int, payload_board_status: int, main_can_status: int, payload_can_status: int, motor_can_status: int, log_number: int, writes_failed: int, force_mavlink1: bool = False) -> None:
+        """
+        Ground Segment Equipment telemetry
+
+        timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
+        loadcell_rocket           : Rocket weight [kg] (type:float)
+        loadcell_vessel           : External tank weight [kg] (type:float)
+        filling_pressure          : Refueling line pressure [Bar] (type:float)
+        vessel_pressure           : Vessel tank pressure [Bar] (type:float)
+        filling_valve_state        : 1 If the filling valve is open (type:uint8_t)
+        venting_valve_state        : 1 If the venting valve is open (type:uint8_t)
+        release_valve_state        : 1 If the release valve is open (type:uint8_t)
+        main_valve_state          : 1 If the main valve is open (type:uint8_t)
+        nitrogen_valve_state        : 1 If the nitrogen valve is open (type:uint8_t)
+        gmm_state                 : State of the GroundModeManager (type:uint8_t)
+        tars_state                : State of Tars (type:uint8_t)
+        battery_voltage           : Battery voltage (type:float)
+        current_consumption        : RIG current [A] (type:float)
+        umbilical_current_consumption        : Umbilical current [A] (type:float)
+        main_board_status         : Main board status (1 if armed) (type:uint8_t)
+        payload_board_status        : Payload board status (1 if armed) (type:uint8_t)
+        main_can_status           : Main CAN status (type:uint8_t)
+        payload_can_status        : Payload CAN status (type:uint8_t)
+        motor_can_status          : Motor CAN status (type:uint8_t)
+        log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+        writes_failed             : Number of fwrite() that failed (type:int32_t)
+
+        """
+        self.send(self.gse_tm_encode(timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_status, payload_board_status, main_can_status, payload_can_status, motor_can_status, log_number, writes_failed), force_mavlink1=force_mavlink1)
+
+    def motor_tm_encode(self, timestamp: int, top_tank_pressure: float, bottom_tank_pressure: float, combustion_chamber_pressure: float, floating_level: int, tank_temperature: float, main_valve_state: int, venting_valve_state: int, battery_voltage: float, log_number: int, writes_failed: int, hil_state: int) -> MAVLink_motor_tm_message:
+        """
+        Motor rocket telemetry
+
+        timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
+        top_tank_pressure         : Tank upper pressure [Bar] (type:float)
+        bottom_tank_pressure        : Tank bottom pressure [Bar] (type:float)
+        combustion_chamber_pressure        : Pressure inside the combustion chamber used for automatic shutdown [Bar] (type:float)
+        floating_level            : Floating level in tank (type:uint8_t)
+        tank_temperature          : Tank temperature (type:float)
+        main_valve_state          : 1 If the main valve is open (type:uint8_t)
+        venting_valve_state        : 1 If the venting valve is open (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)
+        writes_failed             : Number of fwrite() that failed (type:int32_t)
+        hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
+
+        """
+        return MAVLink_motor_tm_message(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, writes_failed, hil_state)
+
+    def motor_tm_send(self, timestamp: int, top_tank_pressure: float, bottom_tank_pressure: float, combustion_chamber_pressure: float, floating_level: int, tank_temperature: float, main_valve_state: int, venting_valve_state: int, battery_voltage: float, log_number: int, writes_failed: int, hil_state: int, force_mavlink1: bool = False) -> None:
+        """
+        Motor rocket telemetry
 
+        timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
+        top_tank_pressure         : Tank upper pressure [Bar] (type:float)
+        bottom_tank_pressure        : Tank bottom pressure [Bar] (type:float)
+        combustion_chamber_pressure        : Pressure inside the combustion chamber used for automatic shutdown [Bar] (type:float)
+        floating_level            : Floating level in tank (type:uint8_t)
+        tank_temperature          : Tank temperature (type:float)
+        main_valve_state          : 1 If the main valve is open (type:uint8_t)
+        venting_valve_state        : 1 If the venting valve is open (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)
+        writes_failed             : Number of fwrite() that failed (type:int32_t)
+        hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
+
+        """
+        self.send(self.motor_tm_encode(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, writes_failed, hil_state), force_mavlink1=force_mavlink1)
diff --git a/mavlink_lib/lyra/lyra.h b/mavlink_lib/lyra/lyra.h
index 488fe5691208e18ca15d92849ba42535bcb0cc26..40c508f60d0050bf07c8bdcd1ee9de4d699e5fc4 100644
--- a/mavlink_lib/lyra/lyra.h
+++ b/mavlink_lib/lyra/lyra.h
@@ -10,8 +10,7 @@
     #error Wrong include order: MAVLINK_LYRA.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
 #endif
 
-#undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -2366241032330709078
+#define MAVLINK_LYRA_XML_HASH 2671519531706814092
 
 #ifdef __cplusplus
 extern "C" {
@@ -20,11 +19,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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 7, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 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, 0, 101, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 170, 161, 99, 83, 54, 37, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 7, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 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, 0, 104, 12, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 16, 46, 28, 20, 44, 53, 77, 29, 170, 161, 99, 83, 54, 38, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #endif
 
 #ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 226, 160, 113, 38, 71, 168, 67, 218, 44, 81, 181, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 110, 22, 65, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 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, 0, 22, 202, 164, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 168, 235, 169, 236, 246, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 110, 22, 65, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 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, 0, 239, 183, 220, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 48, 142, 108, 39, 19, 234, 66, 11, 168, 235, 169, 236, 246, 160, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #endif
 
 #include "../protocol.h"
@@ -43,7 +42,8 @@ typedef enum SysIDs
    MAV_SYSID_PAYLOAD=2, /*  | */
    MAV_SYSID_RIG=3, /*  | */
    MAV_SYSID_GS=4, /*  | */
-   SysIDs_ENUM_END=5, /*  | */
+   MAV_SYSID_ARP=5, /*  | */
+   SysIDs_ENUM_END=6, /*  | */
 } SysIDs;
 #endif
 
@@ -111,7 +111,7 @@ typedef enum SensorsTMList
 } SensorsTMList;
 #endif
 
-/** @brief Enum of the commands */
+/** @brief Enum of the rocket commands */
 #ifndef HAVE_ENUM_MavCommandList
 #define HAVE_ENUM_MavCommandList
 typedef enum MavCommandList
@@ -142,6 +142,25 @@ typedef enum MavCommandList
 } MavCommandList;
 #endif
 
+/** @brief Enum of the ARP commands */
+#ifndef HAVE_ENUM_MavArpCommandList
+#define HAVE_ENUM_MavArpCommandList
+typedef enum MavArpCommandList
+{
+   MAV_ARP_CMD_FORCE_INIT=1, /* Command to force the initialization of ARP | */
+   MAV_ARP_CMD_RESET_ALGORITHM=2, /* Command to reset the algorithm | */
+   MAV_ARP_CMD_RESET_BOARD=3, /* Command to force a reboot | */
+   MAV_ARP_CMD_FORCE_NO_FEEDBACK=4, /* Command to move ARP to the not-feedback mode | */
+   MAV_ARP_CMD_ARM=5, /* Command to arm ARP | */
+   MAV_ARP_CMD_DISARM=6, /* Command to disarm ARP | */
+   MAV_ARP_CMD_FOLLOW=7, /* Command to start Follow loop of ARP | */
+   MAV_ARP_CMD_CALIBRATE=8, /* Command to calibrate ARP | */
+   MAV_ARP_CMD_ENTER_TEST_MODE=9, /* Command to enter the test mode | */
+   MAV_ARP_CMD_EXIT_TEST_MODE=10, /* Command to exit the test mode | */
+   MavArpCommandList_ENUM_END=11, /*  | */
+} MavArpCommandList;
+#endif
+
 /** @brief Enum of all the servos used on Gemini */
 #ifndef HAVE_ENUM_ServosList
 #define HAVE_ENUM_ServosList
@@ -241,6 +260,7 @@ typedef enum PinsList
 #include "./mavlink_msg_arp_tm.h"
 #include "./mavlink_msg_set_antenna_coordinates_arp_tc.h"
 #include "./mavlink_msg_set_rocket_coordinates_arp_tc.h"
+#include "./mavlink_msg_arp_command_tc.h"
 #include "./mavlink_msg_sys_tm.h"
 #include "./mavlink_msg_logger_tm.h"
 #include "./mavlink_msg_mavlink_stats_tm.h"
@@ -259,12 +279,10 @@ typedef enum PinsList
 // base include
 
 
-#undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -2366241032330709078
 
-#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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ARP_TM, MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, 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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_TM", 150 }, { "ATTITUDE_TM", 111 }, { "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 }, { "REGISTRY_COORD_TM", 117 }, { "REGISTRY_FLOAT_TM", 115 }, { "REGISTRY_INT_TM", 116 }, { "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", 151 }, { "SET_ATOMIC_VALVE_TIMING_TC", 30 }, { "SET_COOLING_TIME_TC", 35 }, { "SET_COORDINATES_TC", 13 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 15 }, { "SET_IGNITION_TIME_TC", 33 }, { "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", 152 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_STEPPER_ANGLE_TC", 60 }, { "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_LYRA_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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ARP_TM, MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_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}}}, 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}}}, 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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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", 172 }, { "ARP_TM", 150 }, { "ATTITUDE_TM", 111 }, { "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 }, { "REGISTRY_COORD_TM", 117 }, { "REGISTRY_FLOAT_TM", 115 }, { "REGISTRY_INT_TM", 116 }, { "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", 151 }, { "SET_ATOMIC_VALVE_TIMING_TC", 30 }, { "SET_COOLING_TIME_TC", 35 }, { "SET_COORDINATES_TC", 13 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 15 }, { "SET_IGNITION_TIME_TC", 33 }, { "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", 152 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_STEPPER_ANGLE_TC", 60 }, { "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/lyra/mavlink.h b/mavlink_lib/lyra/mavlink.h
index 01344deccdc490c5123aa4b1a3c2268408fd3fd0..b9c663f8bcb716ee65545253ecaa45b66f135e9d 100644
--- a/mavlink_lib/lyra/mavlink.h
+++ b/mavlink_lib/lyra/mavlink.h
@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -2366241032330709078
+#define MAVLINK_PRIMARY_XML_HASH 2671519531706814092
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 254
diff --git a/mavlink_lib/lyra/mavlink_msg_ack_tm.h b/mavlink_lib/lyra/mavlink_msg_ack_tm.h
index 8abc2a50773e576580ab8179be7c6a2348071c59..ecd2a2bb02a7550a4ef6af0b9df1badb945a4b4f 100644
--- a/mavlink_lib/lyra/mavlink_msg_ack_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_ack_tm.h
@@ -69,6 +69,42 @@ static inline uint16_t mavlink_msg_ack_tm_pack(uint8_t system_id, uint8_t compon
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
 }
 
+/**
+ * @brief Pack a ack_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param recv_msgid  Message id of the received message
+ * @param seq_ack  Sequence number of the received message
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ack_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t recv_msgid, uint8_t seq_ack)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
+    _mav_put_uint8_t(buf, 0, recv_msgid);
+    _mav_put_uint8_t(buf, 1, seq_ack);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
+#else
+    mavlink_ack_tm_t packet;
+    packet.recv_msgid = recv_msgid;
+    packet.seq_ack = seq_ack;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ACK_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a ack_tm message on a channel
  * @param system_id ID of this system
@@ -128,6 +164,20 @@ static inline uint16_t mavlink_msg_ack_tm_encode_chan(uint8_t system_id, uint8_t
     return mavlink_msg_ack_tm_pack_chan(system_id, component_id, chan, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
 }
 
+/**
+ * @brief Encode a ack_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param ack_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ack_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
+{
+    return mavlink_msg_ack_tm_pack_status(system_id, component_id, _status, msg,  ack_tm->recv_msgid, ack_tm->seq_ack);
+}
+
 /**
  * @brief Send a ack_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_ada_tm.h b/mavlink_lib/lyra/mavlink_msg_ada_tm.h
index f96a75c0db6fcd54bea1d9bb6658860e7e998179..d4414c776674a353a3ff83e3de8d296296ea0adf 100644
--- a/mavlink_lib/lyra/mavlink_msg_ada_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_ada_tm.h
@@ -135,6 +135,75 @@ static inline uint16_t mavlink_msg_ada_tm_pack(uint8_t system_id, uint8_t compon
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
 }
 
+/**
+ * @brief Pack a ada_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param state  ADA current state
+ * @param kalman_x0  Kalman state variable 0 (pressure)
+ * @param kalman_x1  Kalman state variable 1 (pressure velocity)
+ * @param kalman_x2  Kalman state variable 2 (pressure acceleration)
+ * @param vertical_speed [m/s] Vertical speed computed by the ADA
+ * @param msl_altitude [m] Altitude w.r.t. mean sea level
+ * @param ref_pressure [Pa] Calibration pressure
+ * @param ref_altitude [m] Calibration altitude
+ * @param ref_temperature [degC] Calibration temperature
+ * @param msl_pressure [Pa] Expected pressure at mean sea level
+ * @param msl_temperature [degC] Expected temperature at mean sea level
+ * @param dpl_altitude [m] Main parachute deployment altituyde
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ada_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, kalman_x0);
+    _mav_put_float(buf, 12, kalman_x1);
+    _mav_put_float(buf, 16, kalman_x2);
+    _mav_put_float(buf, 20, vertical_speed);
+    _mav_put_float(buf, 24, msl_altitude);
+    _mav_put_float(buf, 28, ref_pressure);
+    _mav_put_float(buf, 32, ref_altitude);
+    _mav_put_float(buf, 36, ref_temperature);
+    _mav_put_float(buf, 40, msl_pressure);
+    _mav_put_float(buf, 44, msl_temperature);
+    _mav_put_float(buf, 48, dpl_altitude);
+    _mav_put_uint8_t(buf, 52, state);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
+#else
+    mavlink_ada_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.kalman_x0 = kalman_x0;
+    packet.kalman_x1 = kalman_x1;
+    packet.kalman_x2 = kalman_x2;
+    packet.vertical_speed = vertical_speed;
+    packet.msl_altitude = msl_altitude;
+    packet.ref_pressure = ref_pressure;
+    packet.ref_altitude = ref_altitude;
+    packet.ref_temperature = ref_temperature;
+    packet.msl_pressure = msl_pressure;
+    packet.msl_temperature = msl_temperature;
+    packet.dpl_altitude = dpl_altitude;
+    packet.state = state;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ADA_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a ada_tm message on a channel
  * @param system_id ID of this system
@@ -227,6 +296,20 @@ static inline uint16_t mavlink_msg_ada_tm_encode_chan(uint8_t system_id, uint8_t
     return mavlink_msg_ada_tm_pack_chan(system_id, component_id, chan, msg, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
 }
 
+/**
+ * @brief Encode a ada_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param ada_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ada_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
+{
+    return mavlink_msg_ada_tm_pack_status(system_id, component_id, _status, msg,  ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
+}
+
 /**
  * @brief Send a ada_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_adc_tm.h b/mavlink_lib/lyra/mavlink_msg_adc_tm.h
index ddd0f2ef7947c235fd4f2bc7d7259db63d6ed580..361d27529522a869948409fecc65a02badcaab3d 100644
--- a/mavlink_lib/lyra/mavlink_msg_adc_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_adc_tm.h
@@ -115,6 +115,64 @@ static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t compon
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
 }
 
+/**
+ * @brief Pack a adc_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param sensor_name  Sensor name
+ * @param channel_0 [V] ADC voltage measured on channel 0
+ * @param channel_1 [V] ADC voltage measured on channel 1
+ * @param channel_2 [V] ADC voltage measured on channel 2
+ * @param channel_3 [V] ADC voltage measured on channel 3
+ * @param channel_4 [V] ADC voltage measured on channel 4
+ * @param channel_5 [V] ADC voltage measured on channel 5
+ * @param channel_6 [V] ADC voltage measured on channel 6
+ * @param channel_7 [V] ADC voltage measured on channel 7
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_adc_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, channel_0);
+    _mav_put_float(buf, 12, channel_1);
+    _mav_put_float(buf, 16, channel_2);
+    _mav_put_float(buf, 20, channel_3);
+    _mav_put_float(buf, 24, channel_4);
+    _mav_put_float(buf, 28, channel_5);
+    _mav_put_float(buf, 32, channel_6);
+    _mav_put_float(buf, 36, channel_7);
+    _mav_put_char_array(buf, 40, sensor_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
+#else
+    mavlink_adc_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.channel_0 = channel_0;
+    packet.channel_1 = channel_1;
+    packet.channel_2 = channel_2;
+    packet.channel_3 = channel_3;
+    packet.channel_4 = channel_4;
+    packet.channel_5 = channel_5;
+    packet.channel_6 = channel_6;
+    packet.channel_7 = channel_7;
+    mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ADC_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a adc_tm message on a channel
  * @param system_id ID of this system
@@ -196,6 +254,20 @@ static inline uint16_t mavlink_msg_adc_tm_encode_chan(uint8_t system_id, uint8_t
     return mavlink_msg_adc_tm_pack_chan(system_id, component_id, chan, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
 }
 
+/**
+ * @brief Encode a adc_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param adc_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_adc_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
+{
+    return mavlink_msg_adc_tm_pack_status(system_id, component_id, _status, msg,  adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
+}
+
 /**
  * @brief Send a adc_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_arp_command_tc.h b/mavlink_lib/lyra/mavlink_msg_arp_command_tc.h
index c99ad256649918794e959f284adac8490508482b..0a8311c6cde8ccdb90f014b0284711757b728260 100644
--- a/mavlink_lib/lyra/mavlink_msg_arp_command_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_arp_command_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_arp_command_tc_pack(uint8_t system_id, uint8_
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC);
 }
 
+/**
+ * @brief Pack a arp_command_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param command_id  A member of the MavArpCommandList enum
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_arp_command_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t command_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN];
+    _mav_put_uint8_t(buf, 0, command_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN);
+#else
+    mavlink_arp_command_tc_t packet;
+    packet.command_id = command_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ARP_COMMAND_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a arp_command_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_arp_command_tc_encode_chan(uint8_t system_id,
     return mavlink_msg_arp_command_tc_pack_chan(system_id, component_id, chan, msg, arp_command_tc->command_id);
 }
 
+/**
+ * @brief Encode a arp_command_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param arp_command_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_arp_command_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_arp_command_tc_t* arp_command_tc)
+{
+    return mavlink_msg_arp_command_tc_pack_status(system_id, component_id, _status, msg,  arp_command_tc->command_id);
+}
+
 /**
  * @brief Send a arp_command_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_arp_tm.h b/mavlink_lib/lyra/mavlink_msg_arp_tm.h
index dc4045d218fe505f05fce9d5d18e940f32bb8a7e..712f567cd9406722a2296fa2542785107bff65a1 100644
--- a/mavlink_lib/lyra/mavlink_msg_arp_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_arp_tm.h
@@ -33,6 +33,8 @@ typedef struct __mavlink_arp_tm_t {
  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*/
@@ -40,13 +42,13 @@ typedef struct __mavlink_arp_tm_t {
  uint8_t ethernet_status; /*<  Status flag indicating the status of the ethernet PHY*/
 } mavlink_arp_tm_t;
 
-#define MAVLINK_MSG_ID_ARP_TM_LEN 101
-#define MAVLINK_MSG_ID_ARP_TM_MIN_LEN 101
-#define MAVLINK_MSG_ID_150_LEN 101
-#define MAVLINK_MSG_ID_150_MIN_LEN 101
+#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_CRC 22
-#define MAVLINK_MSG_ID_150_CRC 22
+#define MAVLINK_MSG_ID_ARP_TM_CRC 239
+#define MAVLINK_MSG_ID_150_CRC 239
 
 
 
@@ -54,8 +56,9 @@ typedef struct __mavlink_arp_tm_t {
 #define MAVLINK_MESSAGE_INFO_ARP_TM { \
     150, \
     "ARP_TM", \
-    33, \
+    35, \
     {  { "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) }, \
          { "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) }, \
@@ -70,31 +73,33 @@ 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, 96, offsetof(mavlink_arp_tm_t, gps_fix) }, \
-         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 97, offsetof(mavlink_arp_tm_t, main_radio_present) }, \
+         { "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, 98, offsetof(mavlink_arp_tm_t, payload_radio_present) }, \
+         { "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, 99, offsetof(mavlink_arp_tm_t, ethernet_present) }, \
-         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 100, offsetof(mavlink_arp_tm_t, ethernet_status) }, \
+         { "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) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_ARP_TM { \
     "ARP_TM", \
-    33, \
+    35, \
     {  { "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) }, \
          { "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) }, \
@@ -109,24 +114,25 @@ 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, 96, offsetof(mavlink_arp_tm_t, gps_fix) }, \
-         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 97, offsetof(mavlink_arp_tm_t, main_radio_present) }, \
+         { "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, 98, offsetof(mavlink_arp_tm_t, payload_radio_present) }, \
+         { "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, 99, offsetof(mavlink_arp_tm_t, ethernet_present) }, \
-         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 100, offsetof(mavlink_arp_tm_t, ethernet_status) }, \
+         { "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) }, \
          } \
 }
 #endif
@@ -138,6 +144,7 @@ typedef struct __mavlink_arp_tm_t {
  * @param msg The MAVLink message to compress the data into
  *
  * @param timestamp [us] Timestamp
+ * @param state  State Machine Controller State
  * @param yaw [deg] Current Yaw
  * @param pitch [deg] Current Pitch
  * @param roll [deg] Current Roll
@@ -170,10 +177,11 @@ typedef struct __mavlink_arp_tm_t {
  * @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, 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)
+                               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)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
@@ -205,11 +213,13 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
     _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_uint8_t(buf, 96, gps_fix);
-    _mav_put_uint8_t(buf, 97, main_radio_present);
-    _mav_put_uint8_t(buf, 98, payload_radio_present);
-    _mav_put_uint8_t(buf, 99, ethernet_present);
-    _mav_put_uint8_t(buf, 100, ethernet_status);
+    _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);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN);
 #else
@@ -242,6 +252,8 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
     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;
@@ -255,6 +267,141 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
 }
 
+/**
+ * @brief Pack a arp_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp
+ * @param state  State Machine Controller State
+ * @param yaw [deg] Current Yaw
+ * @param pitch [deg] Current Pitch
+ * @param roll [deg] Current Roll
+ * @param target_yaw [deg] Target Yaw
+ * @param target_pitch [deg] Target Pitch
+ * @param stepperX_pos [deg] StepperX current position wrt the boot position
+ * @param stepperX_delta [deg] StepperX last actuated delta angle
+ * @param stepperX_speed [rps] StepperX current speed
+ * @param stepperY_pos [deg] StepperY current position wrt the boot position
+ * @param stepperY_delta [deg] StepperY last actuated delta angle
+ * @param stepperY_speed [rps] StepperY current Speed
+ * @param gps_latitude [deg] Latitude
+ * @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_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, 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)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, yaw);
+    _mav_put_float(buf, 12, pitch);
+    _mav_put_float(buf, 16, roll);
+    _mav_put_float(buf, 20, target_yaw);
+    _mav_put_float(buf, 24, target_pitch);
+    _mav_put_float(buf, 28, stepperX_pos);
+    _mav_put_float(buf, 32, stepperX_delta);
+    _mav_put_float(buf, 36, stepperX_speed);
+    _mav_put_float(buf, 40, stepperY_pos);
+    _mav_put_float(buf, 44, stepperY_delta);
+    _mav_put_float(buf, 48, stepperY_speed);
+    _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);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN);
+#else
+    mavlink_arp_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.yaw = yaw;
+    packet.pitch = pitch;
+    packet.roll = roll;
+    packet.target_yaw = target_yaw;
+    packet.target_pitch = target_pitch;
+    packet.stepperX_pos = stepperX_pos;
+    packet.stepperX_delta = stepperX_delta;
+    packet.stepperX_speed = stepperX_speed;
+    packet.stepperY_pos = stepperY_pos;
+    packet.stepperY_delta = stepperY_delta;
+    packet.stepperY_speed = stepperY_speed;
+    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
+
+    msg->msgid = MAVLINK_MSG_ID_ARP_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a arp_tm message on a channel
  * @param system_id ID of this system
@@ -262,6 +409,7 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
  * @param chan The MAVLink channel this message will be sent over
  * @param msg The MAVLink message to compress the data into
  * @param timestamp [us] Timestamp
+ * @param state  State Machine Controller State
  * @param yaw [deg] Current Yaw
  * @param pitch [deg] Current Pitch
  * @param roll [deg] Current Roll
@@ -294,11 +442,12 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
  * @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,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)
+                                   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)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
@@ -330,11 +479,13 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c
     _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_uint8_t(buf, 96, gps_fix);
-    _mav_put_uint8_t(buf, 97, main_radio_present);
-    _mav_put_uint8_t(buf, 98, payload_radio_present);
-    _mav_put_uint8_t(buf, 99, ethernet_present);
-    _mav_put_uint8_t(buf, 100, ethernet_status);
+    _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);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN);
 #else
@@ -367,6 +518,8 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c
     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;
@@ -390,7 +543,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->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);
+    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);
 }
 
 /**
@@ -404,7 +557,21 @@ 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->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);
+    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);
+}
+
+/**
+ * @brief Encode a arp_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param arp_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_arp_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_arp_tm_t* arp_tm)
+{
+    return mavlink_msg_arp_tm_pack_status(system_id, component_id, _status, 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);
 }
 
 /**
@@ -412,6 +579,7 @@ static inline uint16_t mavlink_msg_arp_tm_encode_chan(uint8_t system_id, uint8_t
  * @param chan MAVLink channel to send the message
  *
  * @param timestamp [us] Timestamp
+ * @param state  State Machine Controller State
  * @param yaw [deg] Current Yaw
  * @param pitch [deg] Current Pitch
  * @param roll [deg] Current Roll
@@ -444,10 +612,11 @@ static inline uint16_t mavlink_msg_arp_tm_encode_chan(uint8_t system_id, uint8_t
  * @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, 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)
+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)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
@@ -479,11 +648,13 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time
     _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_uint8_t(buf, 96, gps_fix);
-    _mav_put_uint8_t(buf, 97, main_radio_present);
-    _mav_put_uint8_t(buf, 98, payload_radio_present);
-    _mav_put_uint8_t(buf, 99, ethernet_present);
-    _mav_put_uint8_t(buf, 100, ethernet_status);
+    _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_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
@@ -516,6 +687,8 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time
     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;
@@ -534,7 +707,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->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);
+    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);
 #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
@@ -548,7 +721,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, 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)
+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)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -580,11 +753,13 @@ static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     _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_uint8_t(buf, 96, gps_fix);
-    _mav_put_uint8_t(buf, 97, main_radio_present);
-    _mav_put_uint8_t(buf, 98, payload_radio_present);
-    _mav_put_uint8_t(buf, 99, ethernet_present);
-    _mav_put_uint8_t(buf, 100, ethernet_status);
+    _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_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
@@ -617,6 +792,8 @@ static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     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;
@@ -643,6 +820,16 @@ static inline uint64_t mavlink_msg_arp_tm_get_timestamp(const mavlink_message_t*
     return _MAV_RETURN_uint64_t(msg,  0);
 }
 
+/**
+ * @brief Get field state from arp_tm message
+ *
+ * @return  State Machine Controller State
+ */
+static inline uint8_t mavlink_msg_arp_tm_get_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  98);
+}
+
 /**
  * @brief Get field yaw from arp_tm message
  *
@@ -790,7 +977,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,  96);
+    return _MAV_RETURN_uint8_t(msg,  99);
 }
 
 /**
@@ -800,7 +987,7 @@ static inline uint8_t mavlink_msg_arp_tm_get_gps_fix(const mavlink_message_t* ms
  */
 static inline uint8_t mavlink_msg_arp_tm_get_main_radio_present(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  97);
+    return _MAV_RETURN_uint8_t(msg,  100);
 }
 
 /**
@@ -870,7 +1057,7 @@ static inline float mavlink_msg_arp_tm_get_main_rx_rssi(const mavlink_message_t*
  */
 static inline uint8_t mavlink_msg_arp_tm_get_payload_radio_present(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  98);
+    return _MAV_RETURN_uint8_t(msg,  101);
 }
 
 /**
@@ -940,7 +1127,7 @@ static inline float mavlink_msg_arp_tm_get_payload_rx_rssi(const mavlink_message
  */
 static inline uint8_t mavlink_msg_arp_tm_get_ethernet_present(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  99);
+    return _MAV_RETURN_uint8_t(msg,  102);
 }
 
 /**
@@ -950,7 +1137,7 @@ static inline uint8_t mavlink_msg_arp_tm_get_ethernet_present(const mavlink_mess
  */
 static inline uint8_t mavlink_msg_arp_tm_get_ethernet_status(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  100);
+    return _MAV_RETURN_uint8_t(msg,  103);
 }
 
 /**
@@ -963,6 +1150,16 @@ static inline float mavlink_msg_arp_tm_get_battery_voltage(const mavlink_message
     return _MAV_RETURN_float(msg,  72);
 }
 
+/**
+ * @brief Get field log_number from arp_tm message
+ *
+ * @return  Currently active log file, -1 if the logger is inactive
+ */
+static inline int16_t mavlink_msg_arp_tm_get_log_number(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  96);
+}
+
 /**
  * @brief Decode a arp_tm message into a struct
  *
@@ -1000,6 +1197,8 @@ static inline void mavlink_msg_arp_tm_decode(const mavlink_message_t* msg, mavli
     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);
diff --git a/mavlink_lib/lyra/mavlink_msg_attitude_tm.h b/mavlink_lib/lyra/mavlink_msg_attitude_tm.h
index 0a681388622819c22db57c0aa6e4fa55f9dc5d84..55b96a0dda5e02eccade2a50b52deebf52538cf9 100644
--- a/mavlink_lib/lyra/mavlink_msg_attitude_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_attitude_tm.h
@@ -109,6 +109,61 @@ static inline uint16_t mavlink_msg_attitude_tm_pack(uint8_t system_id, uint8_t c
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
 }
 
+/**
+ * @brief Pack a attitude_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param sensor_name  Sensor name
+ * @param roll [deg] Roll angle
+ * @param pitch [deg] Pitch angle
+ * @param yaw [deg] Yaw angle
+ * @param quat_x  Quaternion x component
+ * @param quat_y  Quaternion y component
+ * @param quat_z  Quaternion z component
+ * @param quat_w  Quaternion w component
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_attitude_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, const char *sensor_name, float roll, float pitch, float yaw, float quat_x, float quat_y, float quat_z, float quat_w)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ATTITUDE_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, roll);
+    _mav_put_float(buf, 12, pitch);
+    _mav_put_float(buf, 16, yaw);
+    _mav_put_float(buf, 20, quat_x);
+    _mav_put_float(buf, 24, quat_y);
+    _mav_put_float(buf, 28, quat_z);
+    _mav_put_float(buf, 32, quat_w);
+    _mav_put_char_array(buf, 36, sensor_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
+#else
+    mavlink_attitude_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.roll = roll;
+    packet.pitch = pitch;
+    packet.yaw = yaw;
+    packet.quat_x = quat_x;
+    packet.quat_y = quat_y;
+    packet.quat_z = quat_z;
+    packet.quat_w = quat_w;
+    mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a attitude_tm message on a channel
  * @param system_id ID of this system
@@ -187,6 +242,20 @@ static inline uint16_t mavlink_msg_attitude_tm_encode_chan(uint8_t system_id, ui
     return mavlink_msg_attitude_tm_pack_chan(system_id, component_id, chan, msg, attitude_tm->timestamp, attitude_tm->sensor_name, attitude_tm->roll, attitude_tm->pitch, attitude_tm->yaw, attitude_tm->quat_x, attitude_tm->quat_y, attitude_tm->quat_z, attitude_tm->quat_w);
 }
 
+/**
+ * @brief Encode a attitude_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param attitude_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_attitude_tm_t* attitude_tm)
+{
+    return mavlink_msg_attitude_tm_pack_status(system_id, component_id, _status, msg,  attitude_tm->timestamp, attitude_tm->sensor_name, attitude_tm->roll, attitude_tm->pitch, attitude_tm->yaw, attitude_tm->quat_x, attitude_tm->quat_y, attitude_tm->quat_z, attitude_tm->quat_w);
+}
+
 /**
  * @brief Send a attitude_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_can_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_can_stats_tm.h
index 4bc1ec272ef1ed3729b762021d2ccbacbc2c1681..aec1058eda2e0578e869a46e33f65419e8facdde 100644
--- a/mavlink_lib/lyra/mavlink_msg_can_stats_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_can_stats_tm.h
@@ -81,6 +81,48 @@ static inline uint16_t mavlink_msg_can_stats_tm_pack(uint8_t system_id, uint8_t
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_CRC);
 }
 
+/**
+ * @brief Pack a can_stats_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param payload_bit_rate  Payload only bitrate
+ * @param total_bit_rate  Total bitrate
+ * @param load_percent  Load percent of the BUS
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_can_stats_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, float payload_bit_rate, float total_bit_rate, float load_percent)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_CAN_STATS_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, payload_bit_rate);
+    _mav_put_float(buf, 12, total_bit_rate);
+    _mav_put_float(buf, 16, load_percent);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAN_STATS_TM_LEN);
+#else
+    mavlink_can_stats_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.payload_bit_rate = payload_bit_rate;
+    packet.total_bit_rate = total_bit_rate;
+    packet.load_percent = load_percent;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAN_STATS_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_CAN_STATS_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a can_stats_tm message on a channel
  * @param system_id ID of this system
@@ -146,6 +188,20 @@ static inline uint16_t mavlink_msg_can_stats_tm_encode_chan(uint8_t system_id, u
     return mavlink_msg_can_stats_tm_pack_chan(system_id, component_id, chan, msg, can_stats_tm->timestamp, can_stats_tm->payload_bit_rate, can_stats_tm->total_bit_rate, can_stats_tm->load_percent);
 }
 
+/**
+ * @brief Encode a can_stats_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param can_stats_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_can_stats_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_can_stats_tm_t* can_stats_tm)
+{
+    return mavlink_msg_can_stats_tm_pack_status(system_id, component_id, _status, msg,  can_stats_tm->timestamp, can_stats_tm->payload_bit_rate, can_stats_tm->total_bit_rate, can_stats_tm->load_percent);
+}
+
 /**
  * @brief Send a can_stats_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_command_tc.h b/mavlink_lib/lyra/mavlink_msg_command_tc.h
index a4d0886b3f67df648cfd4ed0b8debc059ecfa272..ad1b1f9952a70f7ab487ac480f7b16dce645b085 100644
--- a/mavlink_lib/lyra/mavlink_msg_command_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_command_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_command_tc_pack(uint8_t system_id, uint8_t co
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
 }
 
+/**
+ * @brief Pack a command_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param command_id  A member of the MavCommandList enum
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_command_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t command_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_COMMAND_TC_LEN];
+    _mav_put_uint8_t(buf, 0, command_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_TC_LEN);
+#else
+    mavlink_command_tc_t packet;
+    packet.command_id = command_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_COMMAND_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a command_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_command_tc_encode_chan(uint8_t system_id, uin
     return mavlink_msg_command_tc_pack_chan(system_id, component_id, chan, msg, command_tc->command_id);
 }
 
+/**
+ * @brief Encode a command_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param command_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_command_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_command_tc_t* command_tc)
+{
+    return mavlink_msg_command_tc_pack_status(system_id, component_id, _status, msg,  command_tc->command_id);
+}
+
 /**
  * @brief Send a command_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_conrig_state_tc.h b/mavlink_lib/lyra/mavlink_msg_conrig_state_tc.h
index c3da8f3c2bca3b8ea850a40a3307f1f50db67626..369ed5ddc03c3a8034fd287320d982483daa493c 100644
--- a/mavlink_lib/lyra/mavlink_msg_conrig_state_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_conrig_state_tc.h
@@ -99,6 +99,57 @@ static inline uint16_t mavlink_msg_conrig_state_tc_pack(uint8_t system_id, uint8
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
 }
 
+/**
+ * @brief Pack a conrig_state_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param ignition_btn  Ignition button pressed
+ * @param filling_valve_btn  Open filling valve pressed
+ * @param venting_valve_btn  Open venting valve pressed
+ * @param release_pressure_btn  Release filling line pressure pressed
+ * @param quick_connector_btn  Detach quick connector pressed
+ * @param start_tars_btn  Startup TARS pressed
+ * @param arm_switch  Arming switch state
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_conrig_state_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t ignition_btn, uint8_t filling_valve_btn, uint8_t venting_valve_btn, uint8_t release_pressure_btn, uint8_t quick_connector_btn, uint8_t start_tars_btn, uint8_t arm_switch)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN];
+    _mav_put_uint8_t(buf, 0, ignition_btn);
+    _mav_put_uint8_t(buf, 1, filling_valve_btn);
+    _mav_put_uint8_t(buf, 2, venting_valve_btn);
+    _mav_put_uint8_t(buf, 3, release_pressure_btn);
+    _mav_put_uint8_t(buf, 4, quick_connector_btn);
+    _mav_put_uint8_t(buf, 5, start_tars_btn);
+    _mav_put_uint8_t(buf, 6, arm_switch);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
+#else
+    mavlink_conrig_state_tc_t packet;
+    packet.ignition_btn = ignition_btn;
+    packet.filling_valve_btn = filling_valve_btn;
+    packet.venting_valve_btn = venting_valve_btn;
+    packet.release_pressure_btn = release_pressure_btn;
+    packet.quick_connector_btn = quick_connector_btn;
+    packet.start_tars_btn = start_tars_btn;
+    packet.arm_switch = arm_switch;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_CONRIG_STATE_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a conrig_state_tc message on a channel
  * @param system_id ID of this system
@@ -173,6 +224,20 @@ static inline uint16_t mavlink_msg_conrig_state_tc_encode_chan(uint8_t system_id
     return mavlink_msg_conrig_state_tc_pack_chan(system_id, component_id, chan, msg, conrig_state_tc->ignition_btn, conrig_state_tc->filling_valve_btn, conrig_state_tc->venting_valve_btn, conrig_state_tc->release_pressure_btn, conrig_state_tc->quick_connector_btn, conrig_state_tc->start_tars_btn, conrig_state_tc->arm_switch);
 }
 
+/**
+ * @brief Encode a conrig_state_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param conrig_state_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_conrig_state_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_conrig_state_tc_t* conrig_state_tc)
+{
+    return mavlink_msg_conrig_state_tc_pack_status(system_id, component_id, _status, msg,  conrig_state_tc->ignition_btn, conrig_state_tc->filling_valve_btn, conrig_state_tc->venting_valve_btn, conrig_state_tc->release_pressure_btn, conrig_state_tc->quick_connector_btn, conrig_state_tc->start_tars_btn, conrig_state_tc->arm_switch);
+}
+
 /**
  * @brief Send a conrig_state_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_current_tm.h b/mavlink_lib/lyra/mavlink_msg_current_tm.h
index 47206857c5d71f9e52ac94532df8bb6660f40792..c9636b114561395c9de72a408b4e20c92aa748f2 100644
--- a/mavlink_lib/lyra/mavlink_msg_current_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_current_tm.h
@@ -73,6 +73,43 @@ static inline uint16_t mavlink_msg_current_tm_pack(uint8_t system_id, uint8_t co
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
 }
 
+/**
+ * @brief Pack a current_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param sensor_name  Sensor name
+ * @param current [A] Current
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_current_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, const char *sensor_name, float current)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_CURRENT_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, current);
+    _mav_put_char_array(buf, 12, sensor_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CURRENT_TM_LEN);
+#else
+    mavlink_current_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.current = current;
+    mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CURRENT_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_CURRENT_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a current_tm message on a channel
  * @param system_id ID of this system
@@ -133,6 +170,20 @@ static inline uint16_t mavlink_msg_current_tm_encode_chan(uint8_t system_id, uin
     return mavlink_msg_current_tm_pack_chan(system_id, component_id, chan, msg, current_tm->timestamp, current_tm->sensor_name, current_tm->current);
 }
 
+/**
+ * @brief Encode a current_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param current_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_current_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_current_tm_t* current_tm)
+{
+    return mavlink_msg_current_tm_pack_status(system_id, component_id, _status, msg,  current_tm->timestamp, current_tm->sensor_name, current_tm->current);
+}
+
 /**
  * @brief Send a current_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_gps_tm.h b/mavlink_lib/lyra/mavlink_msg_gps_tm.h
index d2fd3a488c044808074b29d10d0fb95f0fc92118..17413a3b964dbb72d5fa59c2e17178280d5350e4 100644
--- a/mavlink_lib/lyra/mavlink_msg_gps_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_gps_tm.h
@@ -127,6 +127,70 @@ static inline uint16_t mavlink_msg_gps_tm_pack(uint8_t system_id, uint8_t compon
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
 }
 
+/**
+ * @brief Pack a gps_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param sensor_name  Sensor name
+ * @param fix  Wether the GPS has a FIX
+ * @param latitude [deg] Latitude
+ * @param longitude [deg] Longitude
+ * @param height [m] Altitude
+ * @param vel_north [m/s] Velocity in NED frame (north)
+ * @param vel_east [m/s] Velocity in NED frame (east)
+ * @param vel_down [m/s] Velocity in NED frame (down)
+ * @param speed [m/s] Speed
+ * @param track [deg] Track
+ * @param n_satellites  Number of connected satellites
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gps_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, const char *sensor_name, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_double(buf, 8, latitude);
+    _mav_put_double(buf, 16, longitude);
+    _mav_put_double(buf, 24, height);
+    _mav_put_float(buf, 32, vel_north);
+    _mav_put_float(buf, 36, vel_east);
+    _mav_put_float(buf, 40, vel_down);
+    _mav_put_float(buf, 44, speed);
+    _mav_put_float(buf, 48, track);
+    _mav_put_uint8_t(buf, 72, fix);
+    _mav_put_uint8_t(buf, 73, n_satellites);
+    _mav_put_char_array(buf, 52, sensor_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_TM_LEN);
+#else
+    mavlink_gps_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.latitude = latitude;
+    packet.longitude = longitude;
+    packet.height = height;
+    packet.vel_north = vel_north;
+    packet.vel_east = vel_east;
+    packet.vel_down = vel_down;
+    packet.speed = speed;
+    packet.track = track;
+    packet.fix = fix;
+    packet.n_satellites = n_satellites;
+    mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_GPS_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a gps_tm message on a channel
  * @param system_id ID of this system
@@ -214,6 +278,20 @@ static inline uint16_t mavlink_msg_gps_tm_encode_chan(uint8_t system_id, uint8_t
     return mavlink_msg_gps_tm_pack_chan(system_id, component_id, chan, msg, gps_tm->timestamp, gps_tm->sensor_name, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
 }
 
+/**
+ * @brief Encode a gps_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param gps_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gps_tm_t* gps_tm)
+{
+    return mavlink_msg_gps_tm_pack_status(system_id, component_id, _status, msg,  gps_tm->timestamp, gps_tm->sensor_name, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
+}
+
 /**
  * @brief Send a gps_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_gse_tm.h b/mavlink_lib/lyra/mavlink_msg_gse_tm.h
index 7b5e2186cbd4921bbecf64760bf929ccfc78ccce..ecdb9ad5abf82cfca543f3100ea6233190dc9d35 100644
--- a/mavlink_lib/lyra/mavlink_msg_gse_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_gse_tm.h
@@ -189,6 +189,102 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
 }
 
+/**
+ * @brief Pack a gse_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp in microseconds
+ * @param loadcell_rocket [kg] Rocket weight
+ * @param loadcell_vessel [kg] External tank weight
+ * @param filling_pressure [Bar] Refueling line pressure
+ * @param vessel_pressure [Bar] Vessel tank pressure
+ * @param filling_valve_state  1 If the filling valve is open
+ * @param venting_valve_state  1 If the venting valve is open
+ * @param release_valve_state  1 If the release valve is open
+ * @param main_valve_state  1 If the main valve is open
+ * @param nitrogen_valve_state   1 If the nitrogen valve is open
+ * @param gmm_state  State of the GroundModeManager
+ * @param tars_state  State of Tars
+ * @param battery_voltage  Battery voltage
+ * @param current_consumption [A] RIG current
+ * @param umbilical_current_consumption [A] Umbilical current
+ * @param main_board_status  Main board status (1 if armed)
+ * @param payload_board_status  Payload board status (1 if armed)
+ * @param main_can_status  Main CAN status
+ * @param payload_can_status  Payload CAN status
+ * @param motor_can_status  Motor CAN status
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param writes_failed  Number of fwrite() that failed
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gse_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t gmm_state, uint8_t tars_state, float battery_voltage, float current_consumption, float umbilical_current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t main_can_status, uint8_t payload_can_status, uint8_t motor_can_status, int16_t log_number, int32_t writes_failed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, loadcell_rocket);
+    _mav_put_float(buf, 12, loadcell_vessel);
+    _mav_put_float(buf, 16, filling_pressure);
+    _mav_put_float(buf, 20, vessel_pressure);
+    _mav_put_float(buf, 24, battery_voltage);
+    _mav_put_float(buf, 28, current_consumption);
+    _mav_put_float(buf, 32, umbilical_current_consumption);
+    _mav_put_int32_t(buf, 36, writes_failed);
+    _mav_put_int16_t(buf, 40, log_number);
+    _mav_put_uint8_t(buf, 42, filling_valve_state);
+    _mav_put_uint8_t(buf, 43, venting_valve_state);
+    _mav_put_uint8_t(buf, 44, release_valve_state);
+    _mav_put_uint8_t(buf, 45, main_valve_state);
+    _mav_put_uint8_t(buf, 46, nitrogen_valve_state);
+    _mav_put_uint8_t(buf, 47, gmm_state);
+    _mav_put_uint8_t(buf, 48, tars_state);
+    _mav_put_uint8_t(buf, 49, main_board_status);
+    _mav_put_uint8_t(buf, 50, payload_board_status);
+    _mav_put_uint8_t(buf, 51, main_can_status);
+    _mav_put_uint8_t(buf, 52, payload_can_status);
+    _mav_put_uint8_t(buf, 53, motor_can_status);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GSE_TM_LEN);
+#else
+    mavlink_gse_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.loadcell_rocket = loadcell_rocket;
+    packet.loadcell_vessel = loadcell_vessel;
+    packet.filling_pressure = filling_pressure;
+    packet.vessel_pressure = vessel_pressure;
+    packet.battery_voltage = battery_voltage;
+    packet.current_consumption = current_consumption;
+    packet.umbilical_current_consumption = umbilical_current_consumption;
+    packet.writes_failed = writes_failed;
+    packet.log_number = log_number;
+    packet.filling_valve_state = filling_valve_state;
+    packet.venting_valve_state = venting_valve_state;
+    packet.release_valve_state = release_valve_state;
+    packet.main_valve_state = main_valve_state;
+    packet.nitrogen_valve_state = nitrogen_valve_state;
+    packet.gmm_state = gmm_state;
+    packet.tars_state = tars_state;
+    packet.main_board_status = main_board_status;
+    packet.payload_board_status = payload_board_status;
+    packet.main_can_status = main_can_status;
+    packet.payload_can_status = payload_can_status;
+    packet.motor_can_status = motor_can_status;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GSE_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_GSE_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a gse_tm message on a channel
  * @param system_id ID of this system
@@ -308,6 +404,20 @@ static inline uint16_t mavlink_msg_gse_tm_encode_chan(uint8_t system_id, uint8_t
     return mavlink_msg_gse_tm_pack_chan(system_id, component_id, chan, msg, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->gmm_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->umbilical_current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->main_can_status, gse_tm->payload_can_status, gse_tm->motor_can_status, gse_tm->log_number, gse_tm->writes_failed);
 }
 
+/**
+ * @brief Encode a gse_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param gse_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gse_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gse_tm_t* gse_tm)
+{
+    return mavlink_msg_gse_tm_pack_status(system_id, component_id, _status, msg,  gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->gmm_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->umbilical_current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->main_can_status, gse_tm->payload_can_status, gse_tm->motor_can_status, gse_tm->log_number, gse_tm->writes_failed);
+}
+
 /**
  * @brief Send a gse_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_imu_tm.h b/mavlink_lib/lyra/mavlink_msg_imu_tm.h
index 1ce0401a5bfdcb2013beeb08914ea6115e1da2cb..c07c376474930eaf2ea596d73c08778dcc383d41 100644
--- a/mavlink_lib/lyra/mavlink_msg_imu_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_imu_tm.h
@@ -121,6 +121,67 @@ static inline uint16_t mavlink_msg_imu_tm_pack(uint8_t system_id, uint8_t compon
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
 }
 
+/**
+ * @brief Pack a imu_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param sensor_name  Sensor name
+ * @param acc_x [m/s2] X axis acceleration
+ * @param acc_y [m/s2] Y axis acceleration
+ * @param acc_z [m/s2] Z axis acceleration
+ * @param gyro_x [rad/s] X axis gyro
+ * @param gyro_y [rad/s] Y axis gyro
+ * @param gyro_z [rad/s] Z axis gyro
+ * @param mag_x [uT] X axis compass
+ * @param mag_y [uT] Y axis compass
+ * @param mag_z [uT] Z axis compass
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_imu_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, const char *sensor_name, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_IMU_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, acc_x);
+    _mav_put_float(buf, 12, acc_y);
+    _mav_put_float(buf, 16, acc_z);
+    _mav_put_float(buf, 20, gyro_x);
+    _mav_put_float(buf, 24, gyro_y);
+    _mav_put_float(buf, 28, gyro_z);
+    _mav_put_float(buf, 32, mag_x);
+    _mav_put_float(buf, 36, mag_y);
+    _mav_put_float(buf, 40, mag_z);
+    _mav_put_char_array(buf, 44, sensor_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMU_TM_LEN);
+#else
+    mavlink_imu_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.acc_x = acc_x;
+    packet.acc_y = acc_y;
+    packet.acc_z = acc_z;
+    packet.gyro_x = gyro_x;
+    packet.gyro_y = gyro_y;
+    packet.gyro_z = gyro_z;
+    packet.mag_x = mag_x;
+    packet.mag_y = mag_y;
+    packet.mag_z = mag_z;
+    mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMU_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_IMU_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a imu_tm message on a channel
  * @param system_id ID of this system
@@ -205,6 +266,20 @@ static inline uint16_t mavlink_msg_imu_tm_encode_chan(uint8_t system_id, uint8_t
     return mavlink_msg_imu_tm_pack_chan(system_id, component_id, chan, msg, imu_tm->timestamp, imu_tm->sensor_name, imu_tm->acc_x, imu_tm->acc_y, imu_tm->acc_z, imu_tm->gyro_x, imu_tm->gyro_y, imu_tm->gyro_z, imu_tm->mag_x, imu_tm->mag_y, imu_tm->mag_z);
 }
 
+/**
+ * @brief Encode a imu_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param imu_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_imu_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_imu_tm_t* imu_tm)
+{
+    return mavlink_msg_imu_tm_pack_status(system_id, component_id, _status, msg,  imu_tm->timestamp, imu_tm->sensor_name, imu_tm->acc_x, imu_tm->acc_y, imu_tm->acc_z, imu_tm->gyro_x, imu_tm->gyro_y, imu_tm->gyro_z, imu_tm->mag_x, imu_tm->mag_y, imu_tm->mag_z);
+}
+
 /**
  * @brief Send a imu_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_load_tm.h b/mavlink_lib/lyra/mavlink_msg_load_tm.h
index d93d5e301a3ad5c13003cf6ea37d33329f24ee91..67672c520448b7445bfa6deffc227013dc806639 100644
--- a/mavlink_lib/lyra/mavlink_msg_load_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_load_tm.h
@@ -73,6 +73,43 @@ static inline uint16_t mavlink_msg_load_tm_pack(uint8_t system_id, uint8_t compo
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
 }
 
+/**
+ * @brief Pack a load_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param sensor_name  Sensor name
+ * @param load [kg] Load force
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_load_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, const char *sensor_name, float load)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_LOAD_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, load);
+    _mav_put_char_array(buf, 12, sensor_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOAD_TM_LEN);
+#else
+    mavlink_load_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.load = load;
+    mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOAD_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_LOAD_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a load_tm message on a channel
  * @param system_id ID of this system
@@ -133,6 +170,20 @@ static inline uint16_t mavlink_msg_load_tm_encode_chan(uint8_t system_id, uint8_
     return mavlink_msg_load_tm_pack_chan(system_id, component_id, chan, msg, load_tm->timestamp, load_tm->sensor_name, load_tm->load);
 }
 
+/**
+ * @brief Encode a load_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param load_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_load_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_load_tm_t* load_tm)
+{
+    return mavlink_msg_load_tm_pack_status(system_id, component_id, _status, msg,  load_tm->timestamp, load_tm->sensor_name, load_tm->load);
+}
+
 /**
  * @brief Send a load_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_logger_tm.h b/mavlink_lib/lyra/mavlink_msg_logger_tm.h
index 774424b626afd390bab1065fafad81eea390af1c..d269e60795cb501f65bf7cb834b20d8973f7b4f0 100644
--- a/mavlink_lib/lyra/mavlink_msg_logger_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_logger_tm.h
@@ -123,6 +123,69 @@ static inline uint16_t mavlink_msg_logger_tm_pack(uint8_t system_id, uint8_t com
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
 }
 
+/**
+ * @brief Pack a logger_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param too_large_samples  Number of dropped samples because too large
+ * @param dropped_samples  Number of dropped samples due to fifo full
+ * @param queued_samples  Number of samples written to buffer
+ * @param buffers_filled  Number of buffers filled
+ * @param buffers_written  Number of buffers written to disk
+ * @param writes_failed  Number of fwrite() that failed
+ * @param last_write_error  Error of the last fwrite() that failed
+ * @param average_write_time  Average time to perform an fwrite() of a buffer
+ * @param max_write_time  Max time to perform an fwrite() of a buffer
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_logger_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, int16_t log_number, int32_t too_large_samples, int32_t dropped_samples, int32_t queued_samples, int32_t buffers_filled, int32_t buffers_written, int32_t writes_failed, int32_t last_write_error, int32_t average_write_time, int32_t max_write_time)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_int32_t(buf, 8, too_large_samples);
+    _mav_put_int32_t(buf, 12, dropped_samples);
+    _mav_put_int32_t(buf, 16, queued_samples);
+    _mav_put_int32_t(buf, 20, buffers_filled);
+    _mav_put_int32_t(buf, 24, buffers_written);
+    _mav_put_int32_t(buf, 28, writes_failed);
+    _mav_put_int32_t(buf, 32, last_write_error);
+    _mav_put_int32_t(buf, 36, average_write_time);
+    _mav_put_int32_t(buf, 40, max_write_time);
+    _mav_put_int16_t(buf, 44, log_number);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGER_TM_LEN);
+#else
+    mavlink_logger_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.too_large_samples = too_large_samples;
+    packet.dropped_samples = dropped_samples;
+    packet.queued_samples = queued_samples;
+    packet.buffers_filled = buffers_filled;
+    packet.buffers_written = buffers_written;
+    packet.writes_failed = writes_failed;
+    packet.last_write_error = last_write_error;
+    packet.average_write_time = average_write_time;
+    packet.max_write_time = max_write_time;
+    packet.log_number = log_number;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGER_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_LOGGER_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a logger_tm message on a channel
  * @param system_id ID of this system
@@ -209,6 +272,20 @@ static inline uint16_t mavlink_msg_logger_tm_encode_chan(uint8_t system_id, uint
     return mavlink_msg_logger_tm_pack_chan(system_id, component_id, chan, msg, logger_tm->timestamp, logger_tm->log_number, logger_tm->too_large_samples, logger_tm->dropped_samples, logger_tm->queued_samples, logger_tm->buffers_filled, logger_tm->buffers_written, logger_tm->writes_failed, logger_tm->last_write_error, logger_tm->average_write_time, logger_tm->max_write_time);
 }
 
+/**
+ * @brief Encode a logger_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param logger_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_logger_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_logger_tm_t* logger_tm)
+{
+    return mavlink_msg_logger_tm_pack_status(system_id, component_id, _status, msg,  logger_tm->timestamp, logger_tm->log_number, logger_tm->too_large_samples, logger_tm->dropped_samples, logger_tm->queued_samples, logger_tm->buffers_filled, logger_tm->buffers_written, logger_tm->writes_failed, logger_tm->last_write_error, logger_tm->average_write_time, logger_tm->max_write_time);
+}
+
 /**
  * @brief Send a logger_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_mavlink_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_mavlink_stats_tm.h
index 70bc63247f7ab08a34c0bcd15cae5d11c7727100..805a4376f5074c02aeb86c0d8275575c23e6c451 100644
--- a/mavlink_lib/lyra/mavlink_msg_mavlink_stats_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_mavlink_stats_tm.h
@@ -135,6 +135,75 @@ static inline uint16_t mavlink_msg_mavlink_stats_tm_pack(uint8_t system_id, uint
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
 }
 
+/**
+ * @brief Pack a mavlink_stats_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged 
+ * @param n_send_queue  Current len of the occupied portion of the queue
+ * @param max_send_queue  Max occupied len of the queue 
+ * @param n_send_errors  Number of packet not sent correctly by the TMTC
+ * @param msg_received   Number of received messages
+ * @param buffer_overrun   Number of buffer overruns
+ * @param parse_error   Number of parse errors
+ * @param parse_state   Parsing state machine
+ * @param packet_idx   Index in current packet
+ * @param current_rx_seq   Sequence number of last packet received
+ * @param current_tx_seq   Sequence number of last packet sent  
+ * @param packet_rx_success_count   Received packets
+ * @param packet_rx_drop_count    Number of packet drops   
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mavlink_stats_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, parse_state);
+    _mav_put_uint16_t(buf, 12, n_send_queue);
+    _mav_put_uint16_t(buf, 14, max_send_queue);
+    _mav_put_uint16_t(buf, 16, n_send_errors);
+    _mav_put_uint16_t(buf, 18, packet_rx_success_count);
+    _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
+    _mav_put_uint8_t(buf, 22, msg_received);
+    _mav_put_uint8_t(buf, 23, buffer_overrun);
+    _mav_put_uint8_t(buf, 24, parse_error);
+    _mav_put_uint8_t(buf, 25, packet_idx);
+    _mav_put_uint8_t(buf, 26, current_rx_seq);
+    _mav_put_uint8_t(buf, 27, current_tx_seq);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
+#else
+    mavlink_mavlink_stats_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.parse_state = parse_state;
+    packet.n_send_queue = n_send_queue;
+    packet.max_send_queue = max_send_queue;
+    packet.n_send_errors = n_send_errors;
+    packet.packet_rx_success_count = packet_rx_success_count;
+    packet.packet_rx_drop_count = packet_rx_drop_count;
+    packet.msg_received = msg_received;
+    packet.buffer_overrun = buffer_overrun;
+    packet.parse_error = parse_error;
+    packet.packet_idx = packet_idx;
+    packet.current_rx_seq = current_rx_seq;
+    packet.current_tx_seq = current_tx_seq;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_MAVLINK_STATS_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a mavlink_stats_tm message on a channel
  * @param system_id ID of this system
@@ -227,6 +296,20 @@ static inline uint16_t mavlink_msg_mavlink_stats_tm_encode_chan(uint8_t system_i
     return mavlink_msg_mavlink_stats_tm_pack_chan(system_id, component_id, chan, msg, mavlink_stats_tm->timestamp, mavlink_stats_tm->n_send_queue, mavlink_stats_tm->max_send_queue, mavlink_stats_tm->n_send_errors, mavlink_stats_tm->msg_received, mavlink_stats_tm->buffer_overrun, mavlink_stats_tm->parse_error, mavlink_stats_tm->parse_state, mavlink_stats_tm->packet_idx, mavlink_stats_tm->current_rx_seq, mavlink_stats_tm->current_tx_seq, mavlink_stats_tm->packet_rx_success_count, mavlink_stats_tm->packet_rx_drop_count);
 }
 
+/**
+ * @brief Encode a mavlink_stats_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param mavlink_stats_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mavlink_stats_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
+{
+    return mavlink_msg_mavlink_stats_tm_pack_status(system_id, component_id, _status, msg,  mavlink_stats_tm->timestamp, mavlink_stats_tm->n_send_queue, mavlink_stats_tm->max_send_queue, mavlink_stats_tm->n_send_errors, mavlink_stats_tm->msg_received, mavlink_stats_tm->buffer_overrun, mavlink_stats_tm->parse_error, mavlink_stats_tm->parse_state, mavlink_stats_tm->packet_idx, mavlink_stats_tm->current_rx_seq, mavlink_stats_tm->current_tx_seq, mavlink_stats_tm->packet_rx_success_count, mavlink_stats_tm->packet_rx_drop_count);
+}
+
 /**
  * @brief Send a mavlink_stats_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_mea_tm.h b/mavlink_lib/lyra/mavlink_msg_mea_tm.h
index dafa6490105c6b3af62244e0c8c1f29b73d00d4b..c949dc65855f54c345d6127f85599faaf839c684 100644
--- a/mavlink_lib/lyra/mavlink_msg_mea_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_mea_tm.h
@@ -99,6 +99,57 @@ static inline uint16_t mavlink_msg_mea_tm_pack(uint8_t system_id, uint8_t compon
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
 }
 
+/**
+ * @brief Pack a mea_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param state  MEA current state
+ * @param kalman_x0  Kalman state variable 0 (corrected pressure)
+ * @param kalman_x1  Kalman state variable 1 
+ * @param kalman_x2  Kalman state variable 2 (mass)
+ * @param mass [kg] Mass estimated
+ * @param corrected_pressure [Pa] Corrected pressure
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mea_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_MEA_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, kalman_x0);
+    _mav_put_float(buf, 12, kalman_x1);
+    _mav_put_float(buf, 16, kalman_x2);
+    _mav_put_float(buf, 20, mass);
+    _mav_put_float(buf, 24, corrected_pressure);
+    _mav_put_uint8_t(buf, 28, state);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEA_TM_LEN);
+#else
+    mavlink_mea_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.kalman_x0 = kalman_x0;
+    packet.kalman_x1 = kalman_x1;
+    packet.kalman_x2 = kalman_x2;
+    packet.mass = mass;
+    packet.corrected_pressure = corrected_pressure;
+    packet.state = state;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEA_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_MEA_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a mea_tm message on a channel
  * @param system_id ID of this system
@@ -173,6 +224,20 @@ static inline uint16_t mavlink_msg_mea_tm_encode_chan(uint8_t system_id, uint8_t
     return mavlink_msg_mea_tm_pack_chan(system_id, component_id, chan, msg, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure);
 }
 
+/**
+ * @brief Encode a mea_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param mea_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mea_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mea_tm_t* mea_tm)
+{
+    return mavlink_msg_mea_tm_pack_status(system_id, component_id, _status, msg,  mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure);
+}
+
 /**
  * @brief Send a mea_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_motor_tm.h b/mavlink_lib/lyra/mavlink_msg_motor_tm.h
index 367432dd55007ec30e34a57ae5d38f93e6feb1d8..2b8561344f08d56ef7874c5ca80aad61e146ae67 100644
--- a/mavlink_lib/lyra/mavlink_msg_motor_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_motor_tm.h
@@ -13,18 +13,19 @@ typedef struct __mavlink_motor_tm_t {
  float battery_voltage; /*< [V] Battery voltage*/
  int32_t writes_failed; /*<  Number of fwrite() that failed*/
  int16_t log_number; /*<  Currently active log file, -1 if the logger is inactive*/
+ uint8_t floating_level; /*<  Floating level in tank*/
  uint8_t main_valve_state; /*<  1 If the main valve is open */
  uint8_t venting_valve_state; /*<  1 If the venting valve is open */
  uint8_t hil_state; /*<  1 if the board is currently in HIL mode*/
 } mavlink_motor_tm_t;
 
-#define MAVLINK_MSG_ID_MOTOR_TM_LEN 37
-#define MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN 37
-#define MAVLINK_MSG_ID_213_LEN 37
-#define MAVLINK_MSG_ID_213_MIN_LEN 37
+#define MAVLINK_MSG_ID_MOTOR_TM_LEN 38
+#define MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN 38
+#define MAVLINK_MSG_ID_213_LEN 38
+#define MAVLINK_MSG_ID_213_MIN_LEN 38
 
-#define MAVLINK_MSG_ID_MOTOR_TM_CRC 32
-#define MAVLINK_MSG_ID_213_CRC 32
+#define MAVLINK_MSG_ID_MOTOR_TM_CRC 160
+#define MAVLINK_MSG_ID_213_CRC 160
 
 
 
@@ -32,35 +33,37 @@ typedef struct __mavlink_motor_tm_t {
 #define MAVLINK_MESSAGE_INFO_MOTOR_TM { \
     213, \
     "MOTOR_TM", \
-    11, \
+    12, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_motor_tm_t, timestamp) }, \
          { "top_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_motor_tm_t, top_tank_pressure) }, \
          { "bottom_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_motor_tm_t, bottom_tank_pressure) }, \
          { "combustion_chamber_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_motor_tm_t, combustion_chamber_pressure) }, \
+         { "floating_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_motor_tm_t, floating_level) }, \
          { "tank_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_motor_tm_t, tank_temperature) }, \
-         { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_motor_tm_t, main_valve_state) }, \
-         { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_motor_tm_t, venting_valve_state) }, \
+         { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_motor_tm_t, main_valve_state) }, \
+         { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_motor_tm_t, venting_valve_state) }, \
          { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_motor_tm_t, battery_voltage) }, \
          { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 32, offsetof(mavlink_motor_tm_t, log_number) }, \
          { "writes_failed", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_motor_tm_t, writes_failed) }, \
-         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_motor_tm_t, hil_state) }, \
+         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_motor_tm_t, hil_state) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_MOTOR_TM { \
     "MOTOR_TM", \
-    11, \
+    12, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_motor_tm_t, timestamp) }, \
          { "top_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_motor_tm_t, top_tank_pressure) }, \
          { "bottom_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_motor_tm_t, bottom_tank_pressure) }, \
          { "combustion_chamber_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_motor_tm_t, combustion_chamber_pressure) }, \
+         { "floating_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_motor_tm_t, floating_level) }, \
          { "tank_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_motor_tm_t, tank_temperature) }, \
-         { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_motor_tm_t, main_valve_state) }, \
-         { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_motor_tm_t, venting_valve_state) }, \
+         { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_motor_tm_t, main_valve_state) }, \
+         { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_motor_tm_t, venting_valve_state) }, \
          { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_motor_tm_t, battery_voltage) }, \
          { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 32, offsetof(mavlink_motor_tm_t, log_number) }, \
          { "writes_failed", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_motor_tm_t, writes_failed) }, \
-         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_motor_tm_t, hil_state) }, \
+         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_motor_tm_t, hil_state) }, \
          } \
 }
 #endif
@@ -75,6 +78,7 @@ typedef struct __mavlink_motor_tm_t {
  * @param top_tank_pressure [Bar] Tank upper pressure
  * @param bottom_tank_pressure [Bar] Tank bottom pressure
  * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown
+ * @param floating_level  Floating level in tank
  * @param tank_temperature  Tank temperature
  * @param main_valve_state  1 If the main valve is open 
  * @param venting_valve_state  1 If the venting valve is open 
@@ -85,7 +89,7 @@ typedef struct __mavlink_motor_tm_t {
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, int16_t log_number, int32_t writes_failed, uint8_t hil_state)
+                               uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, int16_t log_number, int32_t writes_failed, uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
@@ -97,9 +101,10 @@ static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t comp
     _mav_put_float(buf, 24, battery_voltage);
     _mav_put_int32_t(buf, 28, writes_failed);
     _mav_put_int16_t(buf, 32, log_number);
-    _mav_put_uint8_t(buf, 34, main_valve_state);
-    _mav_put_uint8_t(buf, 35, venting_valve_state);
-    _mav_put_uint8_t(buf, 36, hil_state);
+    _mav_put_uint8_t(buf, 34, floating_level);
+    _mav_put_uint8_t(buf, 35, main_valve_state);
+    _mav_put_uint8_t(buf, 36, venting_valve_state);
+    _mav_put_uint8_t(buf, 37, hil_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOTOR_TM_LEN);
 #else
@@ -112,6 +117,7 @@ static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t comp
     packet.battery_voltage = battery_voltage;
     packet.writes_failed = writes_failed;
     packet.log_number = log_number;
+    packet.floating_level = floating_level;
     packet.main_valve_state = main_valve_state;
     packet.venting_valve_state = venting_valve_state;
     packet.hil_state = hil_state;
@@ -123,6 +129,72 @@ static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t comp
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
 }
 
+/**
+ * @brief Pack a motor_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp in microseconds
+ * @param top_tank_pressure [Bar] Tank upper pressure
+ * @param bottom_tank_pressure [Bar] Tank bottom pressure
+ * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown
+ * @param floating_level  Floating level in tank
+ * @param tank_temperature  Tank temperature
+ * @param main_valve_state  1 If the main valve is open 
+ * @param venting_valve_state  1 If the venting valve is open 
+ * @param battery_voltage [V] Battery voltage
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param writes_failed  Number of fwrite() that failed
+ * @param hil_state  1 if the board is currently in HIL mode
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_motor_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, int16_t log_number, int32_t writes_failed, uint8_t hil_state)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, top_tank_pressure);
+    _mav_put_float(buf, 12, bottom_tank_pressure);
+    _mav_put_float(buf, 16, combustion_chamber_pressure);
+    _mav_put_float(buf, 20, tank_temperature);
+    _mav_put_float(buf, 24, battery_voltage);
+    _mav_put_int32_t(buf, 28, writes_failed);
+    _mav_put_int16_t(buf, 32, log_number);
+    _mav_put_uint8_t(buf, 34, floating_level);
+    _mav_put_uint8_t(buf, 35, main_valve_state);
+    _mav_put_uint8_t(buf, 36, venting_valve_state);
+    _mav_put_uint8_t(buf, 37, hil_state);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOTOR_TM_LEN);
+#else
+    mavlink_motor_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.top_tank_pressure = top_tank_pressure;
+    packet.bottom_tank_pressure = bottom_tank_pressure;
+    packet.combustion_chamber_pressure = combustion_chamber_pressure;
+    packet.tank_temperature = tank_temperature;
+    packet.battery_voltage = battery_voltage;
+    packet.writes_failed = writes_failed;
+    packet.log_number = log_number;
+    packet.floating_level = floating_level;
+    packet.main_valve_state = main_valve_state;
+    packet.venting_valve_state = venting_valve_state;
+    packet.hil_state = hil_state;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOTOR_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_MOTOR_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a motor_tm message on a channel
  * @param system_id ID of this system
@@ -133,6 +205,7 @@ static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t comp
  * @param top_tank_pressure [Bar] Tank upper pressure
  * @param bottom_tank_pressure [Bar] Tank bottom pressure
  * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown
+ * @param floating_level  Floating level in tank
  * @param tank_temperature  Tank temperature
  * @param main_valve_state  1 If the main valve is open 
  * @param venting_valve_state  1 If the venting valve is open 
@@ -144,7 +217,7 @@ static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t comp
  */
 static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,float top_tank_pressure,float bottom_tank_pressure,float combustion_chamber_pressure,float tank_temperature,uint8_t main_valve_state,uint8_t venting_valve_state,float battery_voltage,int16_t log_number,int32_t writes_failed,uint8_t hil_state)
+                                   uint64_t timestamp,float top_tank_pressure,float bottom_tank_pressure,float combustion_chamber_pressure,uint8_t floating_level,float tank_temperature,uint8_t main_valve_state,uint8_t venting_valve_state,float battery_voltage,int16_t log_number,int32_t writes_failed,uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
@@ -156,9 +229,10 @@ static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t
     _mav_put_float(buf, 24, battery_voltage);
     _mav_put_int32_t(buf, 28, writes_failed);
     _mav_put_int16_t(buf, 32, log_number);
-    _mav_put_uint8_t(buf, 34, main_valve_state);
-    _mav_put_uint8_t(buf, 35, venting_valve_state);
-    _mav_put_uint8_t(buf, 36, hil_state);
+    _mav_put_uint8_t(buf, 34, floating_level);
+    _mav_put_uint8_t(buf, 35, main_valve_state);
+    _mav_put_uint8_t(buf, 36, venting_valve_state);
+    _mav_put_uint8_t(buf, 37, hil_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOTOR_TM_LEN);
 #else
@@ -171,6 +245,7 @@ static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t
     packet.battery_voltage = battery_voltage;
     packet.writes_failed = writes_failed;
     packet.log_number = log_number;
+    packet.floating_level = floating_level;
     packet.main_valve_state = main_valve_state;
     packet.venting_valve_state = venting_valve_state;
     packet.hil_state = hil_state;
@@ -192,7 +267,7 @@ static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t
  */
 static inline uint16_t mavlink_msg_motor_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_motor_tm_t* motor_tm)
 {
-    return mavlink_msg_motor_tm_pack(system_id, component_id, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->log_number, motor_tm->writes_failed, motor_tm->hil_state);
+    return mavlink_msg_motor_tm_pack(system_id, component_id, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->log_number, motor_tm->writes_failed, motor_tm->hil_state);
 }
 
 /**
@@ -206,7 +281,21 @@ static inline uint16_t mavlink_msg_motor_tm_encode(uint8_t system_id, uint8_t co
  */
 static inline uint16_t mavlink_msg_motor_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_motor_tm_t* motor_tm)
 {
-    return mavlink_msg_motor_tm_pack_chan(system_id, component_id, chan, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->log_number, motor_tm->writes_failed, motor_tm->hil_state);
+    return mavlink_msg_motor_tm_pack_chan(system_id, component_id, chan, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->log_number, motor_tm->writes_failed, motor_tm->hil_state);
+}
+
+/**
+ * @brief Encode a motor_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param motor_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_motor_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_motor_tm_t* motor_tm)
+{
+    return mavlink_msg_motor_tm_pack_status(system_id, component_id, _status, msg,  motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->log_number, motor_tm->writes_failed, motor_tm->hil_state);
 }
 
 /**
@@ -217,6 +306,7 @@ static inline uint16_t mavlink_msg_motor_tm_encode_chan(uint8_t system_id, uint8
  * @param top_tank_pressure [Bar] Tank upper pressure
  * @param bottom_tank_pressure [Bar] Tank bottom pressure
  * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown
+ * @param floating_level  Floating level in tank
  * @param tank_temperature  Tank temperature
  * @param main_valve_state  1 If the main valve is open 
  * @param venting_valve_state  1 If the venting valve is open 
@@ -227,7 +317,7 @@ static inline uint16_t mavlink_msg_motor_tm_encode_chan(uint8_t system_id, uint8
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, int16_t log_number, int32_t writes_failed, uint8_t hil_state)
+static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, int16_t log_number, int32_t writes_failed, uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
@@ -239,9 +329,10 @@ static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t ti
     _mav_put_float(buf, 24, battery_voltage);
     _mav_put_int32_t(buf, 28, writes_failed);
     _mav_put_int16_t(buf, 32, log_number);
-    _mav_put_uint8_t(buf, 34, main_valve_state);
-    _mav_put_uint8_t(buf, 35, venting_valve_state);
-    _mav_put_uint8_t(buf, 36, hil_state);
+    _mav_put_uint8_t(buf, 34, floating_level);
+    _mav_put_uint8_t(buf, 35, main_valve_state);
+    _mav_put_uint8_t(buf, 36, venting_valve_state);
+    _mav_put_uint8_t(buf, 37, hil_state);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, buf, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
 #else
@@ -254,6 +345,7 @@ static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t ti
     packet.battery_voltage = battery_voltage;
     packet.writes_failed = writes_failed;
     packet.log_number = log_number;
+    packet.floating_level = floating_level;
     packet.main_valve_state = main_valve_state;
     packet.venting_valve_state = venting_valve_state;
     packet.hil_state = hil_state;
@@ -270,7 +362,7 @@ static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t ti
 static inline void mavlink_msg_motor_tm_send_struct(mavlink_channel_t chan, const mavlink_motor_tm_t* motor_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_motor_tm_send(chan, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->log_number, motor_tm->writes_failed, motor_tm->hil_state);
+    mavlink_msg_motor_tm_send(chan, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->log_number, motor_tm->writes_failed, motor_tm->hil_state);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, (const char *)motor_tm, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
 #endif
@@ -284,7 +376,7 @@ static inline void mavlink_msg_motor_tm_send_struct(mavlink_channel_t chan, cons
   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_motor_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, int16_t log_number, int32_t writes_failed, uint8_t hil_state)
+static inline void mavlink_msg_motor_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, int16_t log_number, int32_t writes_failed, uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -296,9 +388,10 @@ static inline void mavlink_msg_motor_tm_send_buf(mavlink_message_t *msgbuf, mavl
     _mav_put_float(buf, 24, battery_voltage);
     _mav_put_int32_t(buf, 28, writes_failed);
     _mav_put_int16_t(buf, 32, log_number);
-    _mav_put_uint8_t(buf, 34, main_valve_state);
-    _mav_put_uint8_t(buf, 35, venting_valve_state);
-    _mav_put_uint8_t(buf, 36, hil_state);
+    _mav_put_uint8_t(buf, 34, floating_level);
+    _mav_put_uint8_t(buf, 35, main_valve_state);
+    _mav_put_uint8_t(buf, 36, venting_valve_state);
+    _mav_put_uint8_t(buf, 37, hil_state);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, buf, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
 #else
@@ -311,6 +404,7 @@ static inline void mavlink_msg_motor_tm_send_buf(mavlink_message_t *msgbuf, mavl
     packet->battery_voltage = battery_voltage;
     packet->writes_failed = writes_failed;
     packet->log_number = log_number;
+    packet->floating_level = floating_level;
     packet->main_valve_state = main_valve_state;
     packet->venting_valve_state = venting_valve_state;
     packet->hil_state = hil_state;
@@ -365,6 +459,16 @@ static inline float mavlink_msg_motor_tm_get_combustion_chamber_pressure(const m
     return _MAV_RETURN_float(msg,  16);
 }
 
+/**
+ * @brief Get field floating_level from motor_tm message
+ *
+ * @return  Floating level in tank
+ */
+static inline uint8_t mavlink_msg_motor_tm_get_floating_level(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  34);
+}
+
 /**
  * @brief Get field tank_temperature from motor_tm message
  *
@@ -382,7 +486,7 @@ static inline float mavlink_msg_motor_tm_get_tank_temperature(const mavlink_mess
  */
 static inline uint8_t mavlink_msg_motor_tm_get_main_valve_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  34);
+    return _MAV_RETURN_uint8_t(msg,  35);
 }
 
 /**
@@ -392,7 +496,7 @@ static inline uint8_t mavlink_msg_motor_tm_get_main_valve_state(const mavlink_me
  */
 static inline uint8_t mavlink_msg_motor_tm_get_venting_valve_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  35);
+    return _MAV_RETURN_uint8_t(msg,  36);
 }
 
 /**
@@ -432,7 +536,7 @@ static inline int32_t mavlink_msg_motor_tm_get_writes_failed(const mavlink_messa
  */
 static inline uint8_t mavlink_msg_motor_tm_get_hil_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  36);
+    return _MAV_RETURN_uint8_t(msg,  37);
 }
 
 /**
@@ -452,6 +556,7 @@ static inline void mavlink_msg_motor_tm_decode(const mavlink_message_t* msg, mav
     motor_tm->battery_voltage = mavlink_msg_motor_tm_get_battery_voltage(msg);
     motor_tm->writes_failed = mavlink_msg_motor_tm_get_writes_failed(msg);
     motor_tm->log_number = mavlink_msg_motor_tm_get_log_number(msg);
+    motor_tm->floating_level = mavlink_msg_motor_tm_get_floating_level(msg);
     motor_tm->main_valve_state = mavlink_msg_motor_tm_get_main_valve_state(msg);
     motor_tm->venting_valve_state = mavlink_msg_motor_tm_get_venting_valve_state(msg);
     motor_tm->hil_state = mavlink_msg_motor_tm_get_hil_state(msg);
diff --git a/mavlink_lib/lyra/mavlink_msg_nack_tm.h b/mavlink_lib/lyra/mavlink_msg_nack_tm.h
index ecbddd6542c2960a72522b01514efc333a845e75..1b65ddc16a21fc64a0b98bed9e12ade88054aaf5 100644
--- a/mavlink_lib/lyra/mavlink_msg_nack_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_nack_tm.h
@@ -75,6 +75,45 @@ static inline uint16_t mavlink_msg_nack_tm_pack(uint8_t system_id, uint8_t compo
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
 }
 
+/**
+ * @brief Pack a nack_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param recv_msgid  Message id of the received message
+ * @param seq_ack  Sequence number of the received message
+ * @param err_id  Error core that generated the NACK
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_nack_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t recv_msgid, uint8_t seq_ack, uint16_t err_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
+    _mav_put_uint16_t(buf, 0, err_id);
+    _mav_put_uint8_t(buf, 2, recv_msgid);
+    _mav_put_uint8_t(buf, 3, seq_ack);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
+#else
+    mavlink_nack_tm_t packet;
+    packet.err_id = err_id;
+    packet.recv_msgid = recv_msgid;
+    packet.seq_ack = seq_ack;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NACK_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_NACK_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a nack_tm message on a channel
  * @param system_id ID of this system
@@ -137,6 +176,20 @@ static inline uint16_t mavlink_msg_nack_tm_encode_chan(uint8_t system_id, uint8_
     return mavlink_msg_nack_tm_pack_chan(system_id, component_id, chan, msg, nack_tm->recv_msgid, nack_tm->seq_ack, nack_tm->err_id);
 }
 
+/**
+ * @brief Encode a nack_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param nack_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_nack_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
+{
+    return mavlink_msg_nack_tm_pack_status(system_id, component_id, _status, msg,  nack_tm->recv_msgid, nack_tm->seq_ack, nack_tm->err_id);
+}
+
 /**
  * @brief Send a nack_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_nas_tm.h b/mavlink_lib/lyra/mavlink_msg_nas_tm.h
index e91b837c04d4e2bc46c3226696f68c32890b9f08..b429555e84b3a98d595c942a8ff95a39d437a3de 100644
--- a/mavlink_lib/lyra/mavlink_msg_nas_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_nas_tm.h
@@ -171,6 +171,93 @@ static inline uint16_t mavlink_msg_nas_tm_pack(uint8_t system_id, uint8_t compon
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
 }
 
+/**
+ * @brief Pack a nas_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param state  NAS current state
+ * @param nas_n [deg] Navigation system estimated noth position
+ * @param nas_e [deg] Navigation system estimated east position
+ * @param nas_d [m] Navigation system estimated down position
+ * @param nas_vn [m/s] Navigation system estimated north velocity
+ * @param nas_ve [m/s] Navigation system estimated east velocity
+ * @param nas_vd [m/s] Navigation system estimated down velocity
+ * @param nas_qx [deg] Navigation system estimated attitude (qx)
+ * @param nas_qy [deg] Navigation system estimated attitude (qy)
+ * @param nas_qz [deg] Navigation system estimated attitude (qz)
+ * @param nas_qw [deg] Navigation system estimated attitude (qw)
+ * @param nas_bias_x  Navigation system gyroscope bias on x axis
+ * @param nas_bias_y  Navigation system gyroscope bias on y axis
+ * @param nas_bias_z  Navigation system gyroscope bias on z axis
+ * @param ref_pressure [Pa] Calibration pressure
+ * @param ref_temperature [degC] Calibration temperature
+ * @param ref_latitude [deg] Calibration latitude
+ * @param ref_longitude [deg] Calibration longitude
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_nas_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, uint8_t state, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, nas_n);
+    _mav_put_float(buf, 12, nas_e);
+    _mav_put_float(buf, 16, nas_d);
+    _mav_put_float(buf, 20, nas_vn);
+    _mav_put_float(buf, 24, nas_ve);
+    _mav_put_float(buf, 28, nas_vd);
+    _mav_put_float(buf, 32, nas_qx);
+    _mav_put_float(buf, 36, nas_qy);
+    _mav_put_float(buf, 40, nas_qz);
+    _mav_put_float(buf, 44, nas_qw);
+    _mav_put_float(buf, 48, nas_bias_x);
+    _mav_put_float(buf, 52, nas_bias_y);
+    _mav_put_float(buf, 56, nas_bias_z);
+    _mav_put_float(buf, 60, ref_pressure);
+    _mav_put_float(buf, 64, ref_temperature);
+    _mav_put_float(buf, 68, ref_latitude);
+    _mav_put_float(buf, 72, ref_longitude);
+    _mav_put_uint8_t(buf, 76, state);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAS_TM_LEN);
+#else
+    mavlink_nas_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.nas_n = nas_n;
+    packet.nas_e = nas_e;
+    packet.nas_d = nas_d;
+    packet.nas_vn = nas_vn;
+    packet.nas_ve = nas_ve;
+    packet.nas_vd = nas_vd;
+    packet.nas_qx = nas_qx;
+    packet.nas_qy = nas_qy;
+    packet.nas_qz = nas_qz;
+    packet.nas_qw = nas_qw;
+    packet.nas_bias_x = nas_bias_x;
+    packet.nas_bias_y = nas_bias_y;
+    packet.nas_bias_z = nas_bias_z;
+    packet.ref_pressure = ref_pressure;
+    packet.ref_temperature = ref_temperature;
+    packet.ref_latitude = ref_latitude;
+    packet.ref_longitude = ref_longitude;
+    packet.state = state;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAS_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_NAS_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a nas_tm message on a channel
  * @param system_id ID of this system
@@ -281,6 +368,20 @@ static inline uint16_t mavlink_msg_nas_tm_encode_chan(uint8_t system_id, uint8_t
     return mavlink_msg_nas_tm_pack_chan(system_id, component_id, chan, msg, nas_tm->timestamp, nas_tm->state, nas_tm->nas_n, nas_tm->nas_e, nas_tm->nas_d, nas_tm->nas_vn, nas_tm->nas_ve, nas_tm->nas_vd, nas_tm->nas_qx, nas_tm->nas_qy, nas_tm->nas_qz, nas_tm->nas_qw, nas_tm->nas_bias_x, nas_tm->nas_bias_y, nas_tm->nas_bias_z, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude);
 }
 
+/**
+ * @brief Encode a nas_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param nas_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_nas_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_nas_tm_t* nas_tm)
+{
+    return mavlink_msg_nas_tm_pack_status(system_id, component_id, _status, msg,  nas_tm->timestamp, nas_tm->state, nas_tm->nas_n, nas_tm->nas_e, nas_tm->nas_d, nas_tm->nas_vn, nas_tm->nas_ve, nas_tm->nas_vd, nas_tm->nas_qx, nas_tm->nas_qy, nas_tm->nas_qz, nas_tm->nas_qw, nas_tm->nas_bias_x, nas_tm->nas_bias_y, nas_tm->nas_bias_z, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude);
+}
+
 /**
  * @brief Send a nas_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h b/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h
index f3f087bb8c6ae7f4fa3b8181c7e01cf887cbfe36..40354f8a40f646f6cc741d2b4ec42edffa6b97b5 100644
--- a/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h
@@ -333,6 +333,174 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
 }
 
+/**
+ * @brief Pack a payload_flight_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp in microseconds
+ * @param fmm_state  Flight Mode Manager State
+ * @param nas_state  NAS FSM State
+ * @param wes_state  Wind Estimation System FSM State
+ * @param pressure_digi [Pa] Pressure from digital sensor
+ * @param pressure_static [Pa] Pressure from static port
+ * @param airspeed_pitot [m/s] Pitot airspeed
+ * @param altitude_agl [m] Altitude above ground level
+ * @param acc_x [m/s^2] Acceleration on X axis (body)
+ * @param acc_y [m/s^2] Acceleration on Y axis (body)
+ * @param acc_z [m/s^2] Acceleration on Z axis (body)
+ * @param gyro_x [rad/s] Angular speed on X axis (body)
+ * @param gyro_y [rad/s] Angular speed on Y axis (body)
+ * @param gyro_z [rad/s] Angular speed on Z axis (body)
+ * @param mag_x [uT] Magnetic field on X axis (body)
+ * @param mag_y [uT] Magnetic field on Y axis (body)
+ * @param mag_z [uT] Magnetic field on Z axis (body)
+ * @param gps_fix  GPS fix (1 = fix, 0 = no fix)
+ * @param gps_lat [deg] Latitude
+ * @param gps_lon [deg] Longitude
+ * @param gps_alt [m] GPS Altitude
+ * @param left_servo_angle [deg] Left servo motor angle
+ * @param right_servo_angle [deg] Right servo motor angle
+ * @param nas_n [deg] NAS estimated noth position
+ * @param nas_e [deg] NAS estimated east position
+ * @param nas_d [m] NAS estimated down position
+ * @param nas_vn [m/s] NAS estimated north velocity
+ * @param nas_ve [m/s] NAS estimated east velocity
+ * @param nas_vd [m/s] NAS estimated down velocity
+ * @param nas_qx [deg] NAS estimated attitude (qx)
+ * @param nas_qy [deg] NAS estimated attitude (qy)
+ * @param nas_qz [deg] NAS estimated attitude (qz)
+ * @param nas_qw [deg] NAS estimated attitude (qw)
+ * @param nas_bias_x  NAS gyroscope bias on x axis
+ * @param nas_bias_y  NAS gyroscope bias on y axis
+ * @param nas_bias_z  NAS gyroscope bias on z axis
+ * @param wes_n [m/s] Wind estimated north velocity
+ * @param wes_e [m/s] Wind estimated east velocity
+ * @param pin_nosecone  Nosecone pin status (1 = connected, 0 = disconnected)
+ * @param battery_voltage [V] Battery voltage
+ * @param cam_battery_voltage [V] Camera battery voltage
+ * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
+ * @param temperature [degC] Temperature
+ * @param main_can_status  Main CAN status
+ * @param motor_can_status  Motor CAN status
+ * @param rig_can_status  RIG CAN status
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_payload_flight_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, uint8_t cutter_presence, float temperature, uint8_t main_can_status, uint8_t motor_can_status, uint8_t rig_can_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, pressure_digi);
+    _mav_put_float(buf, 12, pressure_static);
+    _mav_put_float(buf, 16, airspeed_pitot);
+    _mav_put_float(buf, 20, altitude_agl);
+    _mav_put_float(buf, 24, acc_x);
+    _mav_put_float(buf, 28, acc_y);
+    _mav_put_float(buf, 32, acc_z);
+    _mav_put_float(buf, 36, gyro_x);
+    _mav_put_float(buf, 40, gyro_y);
+    _mav_put_float(buf, 44, gyro_z);
+    _mav_put_float(buf, 48, mag_x);
+    _mav_put_float(buf, 52, mag_y);
+    _mav_put_float(buf, 56, mag_z);
+    _mav_put_float(buf, 60, gps_lat);
+    _mav_put_float(buf, 64, gps_lon);
+    _mav_put_float(buf, 68, gps_alt);
+    _mav_put_float(buf, 72, left_servo_angle);
+    _mav_put_float(buf, 76, right_servo_angle);
+    _mav_put_float(buf, 80, nas_n);
+    _mav_put_float(buf, 84, nas_e);
+    _mav_put_float(buf, 88, nas_d);
+    _mav_put_float(buf, 92, nas_vn);
+    _mav_put_float(buf, 96, nas_ve);
+    _mav_put_float(buf, 100, nas_vd);
+    _mav_put_float(buf, 104, nas_qx);
+    _mav_put_float(buf, 108, nas_qy);
+    _mav_put_float(buf, 112, nas_qz);
+    _mav_put_float(buf, 116, nas_qw);
+    _mav_put_float(buf, 120, nas_bias_x);
+    _mav_put_float(buf, 124, nas_bias_y);
+    _mav_put_float(buf, 128, nas_bias_z);
+    _mav_put_float(buf, 132, wes_n);
+    _mav_put_float(buf, 136, wes_e);
+    _mav_put_float(buf, 140, battery_voltage);
+    _mav_put_float(buf, 144, cam_battery_voltage);
+    _mav_put_float(buf, 148, temperature);
+    _mav_put_uint8_t(buf, 152, fmm_state);
+    _mav_put_uint8_t(buf, 153, nas_state);
+    _mav_put_uint8_t(buf, 154, wes_state);
+    _mav_put_uint8_t(buf, 155, gps_fix);
+    _mav_put_uint8_t(buf, 156, pin_nosecone);
+    _mav_put_uint8_t(buf, 157, cutter_presence);
+    _mav_put_uint8_t(buf, 158, main_can_status);
+    _mav_put_uint8_t(buf, 159, motor_can_status);
+    _mav_put_uint8_t(buf, 160, rig_can_status);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
+#else
+    mavlink_payload_flight_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.pressure_digi = pressure_digi;
+    packet.pressure_static = pressure_static;
+    packet.airspeed_pitot = airspeed_pitot;
+    packet.altitude_agl = altitude_agl;
+    packet.acc_x = acc_x;
+    packet.acc_y = acc_y;
+    packet.acc_z = acc_z;
+    packet.gyro_x = gyro_x;
+    packet.gyro_y = gyro_y;
+    packet.gyro_z = gyro_z;
+    packet.mag_x = mag_x;
+    packet.mag_y = mag_y;
+    packet.mag_z = mag_z;
+    packet.gps_lat = gps_lat;
+    packet.gps_lon = gps_lon;
+    packet.gps_alt = gps_alt;
+    packet.left_servo_angle = left_servo_angle;
+    packet.right_servo_angle = right_servo_angle;
+    packet.nas_n = nas_n;
+    packet.nas_e = nas_e;
+    packet.nas_d = nas_d;
+    packet.nas_vn = nas_vn;
+    packet.nas_ve = nas_ve;
+    packet.nas_vd = nas_vd;
+    packet.nas_qx = nas_qx;
+    packet.nas_qy = nas_qy;
+    packet.nas_qz = nas_qz;
+    packet.nas_qw = nas_qw;
+    packet.nas_bias_x = nas_bias_x;
+    packet.nas_bias_y = nas_bias_y;
+    packet.nas_bias_z = nas_bias_z;
+    packet.wes_n = wes_n;
+    packet.wes_e = wes_e;
+    packet.battery_voltage = battery_voltage;
+    packet.cam_battery_voltage = cam_battery_voltage;
+    packet.temperature = temperature;
+    packet.fmm_state = fmm_state;
+    packet.nas_state = nas_state;
+    packet.wes_state = wes_state;
+    packet.gps_fix = gps_fix;
+    packet.pin_nosecone = pin_nosecone;
+    packet.cutter_presence = cutter_presence;
+    packet.main_can_status = main_can_status;
+    packet.motor_can_status = motor_can_status;
+    packet.rig_can_status = rig_can_status;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a payload_flight_tm message on a channel
  * @param system_id ID of this system
@@ -524,6 +692,20 @@ static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_
     return mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, chan, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->main_can_status, payload_flight_tm->motor_can_status, payload_flight_tm->rig_can_status);
 }
 
+/**
+ * @brief Encode a payload_flight_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param payload_flight_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_payload_flight_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm)
+{
+    return mavlink_msg_payload_flight_tm_pack_status(system_id, component_id, _status, msg,  payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->main_can_status, payload_flight_tm->motor_can_status, payload_flight_tm->rig_can_status);
+}
+
 /**
  * @brief Send a payload_flight_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h
index d90c4b2002adc1edb5e6203587818b2444ff3911..dbc2cb551536190f3c6a1aaef483009ca95b2570 100644
--- a/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h
@@ -165,6 +165,90 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
 }
 
+/**
+ * @brief Pack a payload_stats_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
+ * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
+ * @param dpl_ts [us] System clock at drouge deployment
+ * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
+ * @param max_z_speed_ts [us] System clock at max vertical speed
+ * @param max_z_speed [m/s] Max measured vertical speed
+ * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
+ * @param max_speed_altitude [m] Altitude at max speed
+ * @param apogee_ts [us] System clock at apogee
+ * @param apogee_lat [deg] Apogee latitude
+ * @param apogee_lon [deg] Apogee longitude
+ * @param apogee_alt [m] Apogee altitude
+ * @param min_pressure [Pa] Apogee pressure - Digital barometer
+ * @param cpu_load  CPU load in percentage
+ * @param free_heap  Amount of available heap in memory
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param writes_failed  Number of fwrite() that failed
+ * @param hil_state  1 if the board is currently in HIL mode
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_payload_stats_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap, int16_t log_number, int32_t writes_failed, uint8_t hil_state)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
+    _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
+    _mav_put_uint64_t(buf, 8, dpl_ts);
+    _mav_put_uint64_t(buf, 16, max_z_speed_ts);
+    _mav_put_uint64_t(buf, 24, apogee_ts);
+    _mav_put_float(buf, 32, liftoff_max_acc);
+    _mav_put_float(buf, 36, dpl_max_acc);
+    _mav_put_float(buf, 40, max_z_speed);
+    _mav_put_float(buf, 44, max_airspeed_pitot);
+    _mav_put_float(buf, 48, max_speed_altitude);
+    _mav_put_float(buf, 52, apogee_lat);
+    _mav_put_float(buf, 56, apogee_lon);
+    _mav_put_float(buf, 60, apogee_alt);
+    _mav_put_float(buf, 64, min_pressure);
+    _mav_put_float(buf, 68, cpu_load);
+    _mav_put_uint32_t(buf, 72, free_heap);
+    _mav_put_int32_t(buf, 76, writes_failed);
+    _mav_put_int16_t(buf, 80, log_number);
+    _mav_put_uint8_t(buf, 82, hil_state);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
+#else
+    mavlink_payload_stats_tm_t packet;
+    packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
+    packet.dpl_ts = dpl_ts;
+    packet.max_z_speed_ts = max_z_speed_ts;
+    packet.apogee_ts = apogee_ts;
+    packet.liftoff_max_acc = liftoff_max_acc;
+    packet.dpl_max_acc = dpl_max_acc;
+    packet.max_z_speed = max_z_speed;
+    packet.max_airspeed_pitot = max_airspeed_pitot;
+    packet.max_speed_altitude = max_speed_altitude;
+    packet.apogee_lat = apogee_lat;
+    packet.apogee_lon = apogee_lon;
+    packet.apogee_alt = apogee_alt;
+    packet.min_pressure = min_pressure;
+    packet.cpu_load = cpu_load;
+    packet.free_heap = free_heap;
+    packet.writes_failed = writes_failed;
+    packet.log_number = log_number;
+    packet.hil_state = hil_state;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_PAYLOAD_STATS_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a payload_stats_tm message on a channel
  * @param system_id ID of this system
@@ -272,6 +356,20 @@ static inline uint16_t mavlink_msg_payload_stats_tm_encode_chan(uint8_t system_i
     return mavlink_msg_payload_stats_tm_pack_chan(system_id, component_id, chan, msg, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap, payload_stats_tm->log_number, payload_stats_tm->writes_failed, payload_stats_tm->hil_state);
 }
 
+/**
+ * @brief Encode a payload_stats_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param payload_stats_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_payload_stats_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_payload_stats_tm_t* payload_stats_tm)
+{
+    return mavlink_msg_payload_stats_tm_pack_status(system_id, component_id, _status, msg,  payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap, payload_stats_tm->log_number, payload_stats_tm->writes_failed, payload_stats_tm->hil_state);
+}
+
 /**
  * @brief Send a payload_stats_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_pin_tm.h b/mavlink_lib/lyra/mavlink_msg_pin_tm.h
index 7664139b91883710113db1c6e2f79d879b1634c8..297efe3d6b1d5e10583580ccf50875c5da802fde 100644
--- a/mavlink_lib/lyra/mavlink_msg_pin_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_pin_tm.h
@@ -87,6 +87,51 @@ static inline uint16_t mavlink_msg_pin_tm_pack(uint8_t system_id, uint8_t compon
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
 }
 
+/**
+ * @brief Pack a pin_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp
+ * @param pin_id  A member of the PinsList enum
+ * @param last_change_timestamp  Last change timestamp of pin
+ * @param changes_counter  Number of changes of pin
+ * @param current_state  Current state of pin
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_pin_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, uint8_t pin_id, uint64_t last_change_timestamp, uint8_t changes_counter, uint8_t current_state)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_PIN_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint64_t(buf, 8, last_change_timestamp);
+    _mav_put_uint8_t(buf, 16, pin_id);
+    _mav_put_uint8_t(buf, 17, changes_counter);
+    _mav_put_uint8_t(buf, 18, current_state);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PIN_TM_LEN);
+#else
+    mavlink_pin_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.last_change_timestamp = last_change_timestamp;
+    packet.pin_id = pin_id;
+    packet.changes_counter = changes_counter;
+    packet.current_state = current_state;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PIN_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_PIN_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a pin_tm message on a channel
  * @param system_id ID of this system
@@ -155,6 +200,20 @@ static inline uint16_t mavlink_msg_pin_tm_encode_chan(uint8_t system_id, uint8_t
     return mavlink_msg_pin_tm_pack_chan(system_id, component_id, chan, msg, pin_tm->timestamp, pin_tm->pin_id, pin_tm->last_change_timestamp, pin_tm->changes_counter, pin_tm->current_state);
 }
 
+/**
+ * @brief Encode a pin_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param pin_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_pin_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_pin_tm_t* pin_tm)
+{
+    return mavlink_msg_pin_tm_pack_status(system_id, component_id, _status, msg,  pin_tm->timestamp, pin_tm->pin_id, pin_tm->last_change_timestamp, pin_tm->changes_counter, pin_tm->current_state);
+}
+
 /**
  * @brief Send a pin_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_ping_tc.h b/mavlink_lib/lyra/mavlink_msg_ping_tc.h
index 99a2895f9933675f201a98a080067ebf3b33bb66..184dad52f7e96dfd290aeca38bb0e7e65f9daa45 100644
--- a/mavlink_lib/lyra/mavlink_msg_ping_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_ping_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_ping_tc_pack(uint8_t system_id, uint8_t compo
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
 }
 
+/**
+ * @brief Pack a ping_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp  Timestamp to identify when it was sent
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ping_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_PING_TC_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
+#else
+    mavlink_ping_tc_t packet;
+    packet.timestamp = timestamp;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_PING_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a ping_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_ping_tc_encode_chan(uint8_t system_id, uint8_
     return mavlink_msg_ping_tc_pack_chan(system_id, component_id, chan, msg, ping_tc->timestamp);
 }
 
+/**
+ * @brief Encode a ping_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param ping_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ping_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
+{
+    return mavlink_msg_ping_tc_pack_status(system_id, component_id, _status, msg,  ping_tc->timestamp);
+}
+
 /**
  * @brief Send a ping_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_pressure_tm.h b/mavlink_lib/lyra/mavlink_msg_pressure_tm.h
index 11381c5195df40006134a28fbeb17c224bd760ef..0ca9ff6611b092228198c424e915f85e133c46e5 100644
--- a/mavlink_lib/lyra/mavlink_msg_pressure_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_pressure_tm.h
@@ -73,6 +73,43 @@ static inline uint16_t mavlink_msg_pressure_tm_pack(uint8_t system_id, uint8_t c
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
 }
 
+/**
+ * @brief Pack a pressure_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param sensor_name  Sensor name
+ * @param pressure [Pa] Pressure of the digital barometer
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_pressure_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, const char *sensor_name, float pressure)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_PRESSURE_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, pressure);
+    _mav_put_char_array(buf, 12, sensor_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
+#else
+    mavlink_pressure_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.pressure = pressure;
+    mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_PRESSURE_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a pressure_tm message on a channel
  * @param system_id ID of this system
@@ -133,6 +170,20 @@ static inline uint16_t mavlink_msg_pressure_tm_encode_chan(uint8_t system_id, ui
     return mavlink_msg_pressure_tm_pack_chan(system_id, component_id, chan, msg, pressure_tm->timestamp, pressure_tm->sensor_name, pressure_tm->pressure);
 }
 
+/**
+ * @brief Encode a pressure_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param pressure_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_pressure_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_pressure_tm_t* pressure_tm)
+{
+    return mavlink_msg_pressure_tm_pack_status(system_id, component_id, _status, msg,  pressure_tm->timestamp, pressure_tm->sensor_name, pressure_tm->pressure);
+}
+
 /**
  * @brief Send a pressure_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_raw_event_tc.h b/mavlink_lib/lyra/mavlink_msg_raw_event_tc.h
index f08048e75040f7d058e4e538f4f9763b08daf7e3..5027009b0d44c5d7bddc694160acb6871af528d2 100644
--- a/mavlink_lib/lyra/mavlink_msg_raw_event_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_raw_event_tc.h
@@ -69,6 +69,42 @@ static inline uint16_t mavlink_msg_raw_event_tc_pack(uint8_t system_id, uint8_t
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
 }
 
+/**
+ * @brief Pack a raw_event_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param topic_id  Id of the topic to which the event should be posted
+ * @param event_id  Id of the event to be posted
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_raw_event_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t topic_id, uint8_t event_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
+    _mav_put_uint8_t(buf, 0, topic_id);
+    _mav_put_uint8_t(buf, 1, event_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
+#else
+    mavlink_raw_event_tc_t packet;
+    packet.topic_id = topic_id;
+    packet.event_id = event_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a raw_event_tc message on a channel
  * @param system_id ID of this system
@@ -128,6 +164,20 @@ static inline uint16_t mavlink_msg_raw_event_tc_encode_chan(uint8_t system_id, u
     return mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, chan, msg, raw_event_tc->topic_id, raw_event_tc->event_id);
 }
 
+/**
+ * @brief Encode a raw_event_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param raw_event_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_raw_event_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
+{
+    return mavlink_msg_raw_event_tc_pack_status(system_id, component_id, _status, msg,  raw_event_tc->topic_id, raw_event_tc->event_id);
+}
+
 /**
  * @brief Send a raw_event_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_registry_coord_tm.h b/mavlink_lib/lyra/mavlink_msg_registry_coord_tm.h
index e4c2e071a0582bafdb95b0e153ad2557a44407d5..c75cf7d585a39fe092e272c5d44d69f1bd4c4ead 100644
--- a/mavlink_lib/lyra/mavlink_msg_registry_coord_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_registry_coord_tm.h
@@ -85,6 +85,49 @@ static inline uint16_t mavlink_msg_registry_coord_tm_pack(uint8_t system_id, uin
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REGISTRY_COORD_TM_MIN_LEN, MAVLINK_MSG_ID_REGISTRY_COORD_TM_LEN, MAVLINK_MSG_ID_REGISTRY_COORD_TM_CRC);
 }
 
+/**
+ * @brief Pack a registry_coord_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp
+ * @param key_id  Id of this configuration entry
+ * @param key_name  Name of this configuration entry
+ * @param latitude [deg] Latitude in this configuration
+ * @param longitude [deg] Latitude in this configuration
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_registry_coord_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, uint32_t key_id, const char *key_name, float latitude, float longitude)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_REGISTRY_COORD_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, key_id);
+    _mav_put_float(buf, 12, latitude);
+    _mav_put_float(buf, 16, longitude);
+    _mav_put_char_array(buf, 20, key_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REGISTRY_COORD_TM_LEN);
+#else
+    mavlink_registry_coord_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.key_id = key_id;
+    packet.latitude = latitude;
+    packet.longitude = longitude;
+    mav_array_memcpy(packet.key_name, key_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REGISTRY_COORD_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_REGISTRY_COORD_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_REGISTRY_COORD_TM_MIN_LEN, MAVLINK_MSG_ID_REGISTRY_COORD_TM_LEN, MAVLINK_MSG_ID_REGISTRY_COORD_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_REGISTRY_COORD_TM_MIN_LEN, MAVLINK_MSG_ID_REGISTRY_COORD_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a registry_coord_tm message on a channel
  * @param system_id ID of this system
@@ -151,6 +194,20 @@ static inline uint16_t mavlink_msg_registry_coord_tm_encode_chan(uint8_t system_
     return mavlink_msg_registry_coord_tm_pack_chan(system_id, component_id, chan, msg, registry_coord_tm->timestamp, registry_coord_tm->key_id, registry_coord_tm->key_name, registry_coord_tm->latitude, registry_coord_tm->longitude);
 }
 
+/**
+ * @brief Encode a registry_coord_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param registry_coord_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_registry_coord_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_registry_coord_tm_t* registry_coord_tm)
+{
+    return mavlink_msg_registry_coord_tm_pack_status(system_id, component_id, _status, msg,  registry_coord_tm->timestamp, registry_coord_tm->key_id, registry_coord_tm->key_name, registry_coord_tm->latitude, registry_coord_tm->longitude);
+}
+
 /**
  * @brief Send a registry_coord_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_registry_float_tm.h b/mavlink_lib/lyra/mavlink_msg_registry_float_tm.h
index 68fd8f76aa37571aae3d3e5a8b2d2564487cbbfc..973653c9949a4e0e8f8c133ed3e93c970191f852 100644
--- a/mavlink_lib/lyra/mavlink_msg_registry_float_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_registry_float_tm.h
@@ -79,6 +79,46 @@ static inline uint16_t mavlink_msg_registry_float_tm_pack(uint8_t system_id, uin
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_MIN_LEN, MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_LEN, MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_CRC);
 }
 
+/**
+ * @brief Pack a registry_float_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp
+ * @param key_id  Id of this configuration entry
+ * @param key_name  Name of this configuration entry
+ * @param value  Value of this configuration
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_registry_float_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, uint32_t key_id, const char *key_name, float value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, key_id);
+    _mav_put_float(buf, 12, value);
+    _mav_put_char_array(buf, 16, key_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_LEN);
+#else
+    mavlink_registry_float_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.key_id = key_id;
+    packet.value = value;
+    mav_array_memcpy(packet.key_name, key_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_REGISTRY_FLOAT_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_MIN_LEN, MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_LEN, MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_MIN_LEN, MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a registry_float_tm message on a channel
  * @param system_id ID of this system
@@ -142,6 +182,20 @@ static inline uint16_t mavlink_msg_registry_float_tm_encode_chan(uint8_t system_
     return mavlink_msg_registry_float_tm_pack_chan(system_id, component_id, chan, msg, registry_float_tm->timestamp, registry_float_tm->key_id, registry_float_tm->key_name, registry_float_tm->value);
 }
 
+/**
+ * @brief Encode a registry_float_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param registry_float_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_registry_float_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_registry_float_tm_t* registry_float_tm)
+{
+    return mavlink_msg_registry_float_tm_pack_status(system_id, component_id, _status, msg,  registry_float_tm->timestamp, registry_float_tm->key_id, registry_float_tm->key_name, registry_float_tm->value);
+}
+
 /**
  * @brief Send a registry_float_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_registry_int_tm.h b/mavlink_lib/lyra/mavlink_msg_registry_int_tm.h
index fd0786614f86a7d02864e8204e00b766d1acb121..17e04e48302e55253db5229e9d276749a9fcae93 100644
--- a/mavlink_lib/lyra/mavlink_msg_registry_int_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_registry_int_tm.h
@@ -79,6 +79,46 @@ static inline uint16_t mavlink_msg_registry_int_tm_pack(uint8_t system_id, uint8
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REGISTRY_INT_TM_MIN_LEN, MAVLINK_MSG_ID_REGISTRY_INT_TM_LEN, MAVLINK_MSG_ID_REGISTRY_INT_TM_CRC);
 }
 
+/**
+ * @brief Pack a registry_int_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp
+ * @param key_id  Id of this configuration entry
+ * @param key_name  Name of this configuration entry
+ * @param value  Value of this configuration
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_registry_int_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, uint32_t key_id, const char *key_name, uint32_t value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_REGISTRY_INT_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, key_id);
+    _mav_put_uint32_t(buf, 12, value);
+    _mav_put_char_array(buf, 16, key_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REGISTRY_INT_TM_LEN);
+#else
+    mavlink_registry_int_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.key_id = key_id;
+    packet.value = value;
+    mav_array_memcpy(packet.key_name, key_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REGISTRY_INT_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_REGISTRY_INT_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_REGISTRY_INT_TM_MIN_LEN, MAVLINK_MSG_ID_REGISTRY_INT_TM_LEN, MAVLINK_MSG_ID_REGISTRY_INT_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_REGISTRY_INT_TM_MIN_LEN, MAVLINK_MSG_ID_REGISTRY_INT_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a registry_int_tm message on a channel
  * @param system_id ID of this system
@@ -142,6 +182,20 @@ static inline uint16_t mavlink_msg_registry_int_tm_encode_chan(uint8_t system_id
     return mavlink_msg_registry_int_tm_pack_chan(system_id, component_id, chan, msg, registry_int_tm->timestamp, registry_int_tm->key_id, registry_int_tm->key_name, registry_int_tm->value);
 }
 
+/**
+ * @brief Encode a registry_int_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param registry_int_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_registry_int_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_registry_int_tm_t* registry_int_tm)
+{
+    return mavlink_msg_registry_int_tm_pack_status(system_id, component_id, _status, msg,  registry_int_tm->timestamp, registry_int_tm->key_id, registry_int_tm->key_name, registry_int_tm->value);
+}
+
 /**
  * @brief Send a registry_int_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_reset_servo_tc.h b/mavlink_lib/lyra/mavlink_msg_reset_servo_tc.h
index 6a7c1b4e39eafbfb3c316260de23a6716df10888..e12930a90394192267a6d8d96b96e324774fe6bd 100644
--- a/mavlink_lib/lyra/mavlink_msg_reset_servo_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_reset_servo_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_reset_servo_tc_pack(uint8_t system_id, uint8_
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
 }
 
+/**
+ * @brief Pack a reset_servo_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param servo_id  A member of the ServosList enum
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_reset_servo_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t servo_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_RESET_SERVO_TC_LEN];
+    _mav_put_uint8_t(buf, 0, servo_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
+#else
+    mavlink_reset_servo_tc_t packet;
+    packet.servo_id = servo_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_RESET_SERVO_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a reset_servo_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_reset_servo_tc_encode_chan(uint8_t system_id,
     return mavlink_msg_reset_servo_tc_pack_chan(system_id, component_id, chan, msg, reset_servo_tc->servo_id);
 }
 
+/**
+ * @brief Encode a reset_servo_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param reset_servo_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_reset_servo_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_reset_servo_tc_t* reset_servo_tc)
+{
+    return mavlink_msg_reset_servo_tc_pack_status(system_id, component_id, _status, msg,  reset_servo_tc->servo_id);
+}
+
 /**
  * @brief Send a reset_servo_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_rocket_flight_tm.h b/mavlink_lib/lyra/mavlink_msg_rocket_flight_tm.h
index 325430d1bd0a07d665cc524125aa70ff6c761e3f..c757c41455be453040a0d486ff1e662893670bf1 100644
--- a/mavlink_lib/lyra/mavlink_msg_rocket_flight_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_rocket_flight_tm.h
@@ -369,6 +369,192 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
 }
 
+/**
+ * @brief Pack a rocket_flight_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp in microseconds
+ * @param ada_state  ADA Controller State
+ * @param fmm_state  Flight Mode Manager State
+ * @param dpl_state  Deployment Controller State
+ * @param abk_state  Airbrake FSM state
+ * @param nas_state  NAS FSM State
+ * @param mea_state  MEA Controller State
+ * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
+ * @param pressure_digi [Pa] Pressure from digital sensor
+ * @param pressure_static [Pa] Pressure from static port
+ * @param pressure_dpl [Pa] Pressure from deployment vane sensor
+ * @param airspeed_pitot [m/s] Pitot airspeed
+ * @param altitude_agl [m] Altitude above ground level
+ * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
+ * @param mea_mass [kg] Mass estimated by MEA
+ * @param acc_x [m/s^2] Acceleration on X axis (body)
+ * @param acc_y [m/s^2] Acceleration on Y axis (body)
+ * @param acc_z [m/s^2] Acceleration on Z axis (body)
+ * @param gyro_x [rad/s] Angular speed on X axis (body)
+ * @param gyro_y [rad/s] Angular speed on Y axis (body)
+ * @param gyro_z [rad/s] Angular speed on Z axis (body)
+ * @param mag_x [uT] Magnetic field on X axis (body)
+ * @param mag_y [uT] Magnetic field on Y axis (body)
+ * @param mag_z [uT] Magnetic field on Z axis (body)
+ * @param gps_fix  GPS fix (1 = fix, 0 = no fix)
+ * @param gps_lat [deg] Latitude
+ * @param gps_lon [deg] Longitude
+ * @param gps_alt [m] GPS Altitude
+ * @param abk_angle [deg] Air Brakes angle
+ * @param nas_n [deg] NAS estimated noth position
+ * @param nas_e [deg] NAS estimated east position
+ * @param nas_d [m] NAS estimated down position
+ * @param nas_vn [m/s] NAS estimated north velocity
+ * @param nas_ve [m/s] NAS estimated east velocity
+ * @param nas_vd [m/s] NAS estimated down velocity
+ * @param nas_qx [deg] NAS estimated attitude (qx)
+ * @param nas_qy [deg] NAS estimated attitude (qy)
+ * @param nas_qz [deg] NAS estimated attitude (qz)
+ * @param nas_qw [deg] NAS estimated attitude (qw)
+ * @param nas_bias_x  NAS gyroscope bias on x axis
+ * @param nas_bias_y  NAS gyroscope bias on y axis
+ * @param nas_bias_z  NAS gyroscope bias on z axis
+ * @param pin_launch  Launch pin status (1 = connected, 0 = disconnected)
+ * @param pin_nosecone  Nosecone pin status (1 = connected, 0 = disconnected)
+ * @param pin_expulsion  Servo sensor status (1 = actuated, 0 = idle)
+ * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
+ * @param battery_voltage [V] Battery voltage
+ * @param cam_battery_voltage [V] Camera battery voltage
+ * @param temperature [degC] Temperature
+ * @param payload_can_status  Payload CAN status
+ * @param motor_can_status  Motor CAN status
+ * @param rig_can_status  RIG CAN status
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rocket_flight_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float temperature, uint8_t payload_can_status, uint8_t motor_can_status, uint8_t rig_can_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, pressure_ada);
+    _mav_put_float(buf, 12, pressure_digi);
+    _mav_put_float(buf, 16, pressure_static);
+    _mav_put_float(buf, 20, pressure_dpl);
+    _mav_put_float(buf, 24, airspeed_pitot);
+    _mav_put_float(buf, 28, altitude_agl);
+    _mav_put_float(buf, 32, ada_vert_speed);
+    _mav_put_float(buf, 36, mea_mass);
+    _mav_put_float(buf, 40, acc_x);
+    _mav_put_float(buf, 44, acc_y);
+    _mav_put_float(buf, 48, acc_z);
+    _mav_put_float(buf, 52, gyro_x);
+    _mav_put_float(buf, 56, gyro_y);
+    _mav_put_float(buf, 60, gyro_z);
+    _mav_put_float(buf, 64, mag_x);
+    _mav_put_float(buf, 68, mag_y);
+    _mav_put_float(buf, 72, mag_z);
+    _mav_put_float(buf, 76, gps_lat);
+    _mav_put_float(buf, 80, gps_lon);
+    _mav_put_float(buf, 84, gps_alt);
+    _mav_put_float(buf, 88, abk_angle);
+    _mav_put_float(buf, 92, nas_n);
+    _mav_put_float(buf, 96, nas_e);
+    _mav_put_float(buf, 100, nas_d);
+    _mav_put_float(buf, 104, nas_vn);
+    _mav_put_float(buf, 108, nas_ve);
+    _mav_put_float(buf, 112, nas_vd);
+    _mav_put_float(buf, 116, nas_qx);
+    _mav_put_float(buf, 120, nas_qy);
+    _mav_put_float(buf, 124, nas_qz);
+    _mav_put_float(buf, 128, nas_qw);
+    _mav_put_float(buf, 132, nas_bias_x);
+    _mav_put_float(buf, 136, nas_bias_y);
+    _mav_put_float(buf, 140, nas_bias_z);
+    _mav_put_float(buf, 144, battery_voltage);
+    _mav_put_float(buf, 148, cam_battery_voltage);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, ada_state);
+    _mav_put_uint8_t(buf, 157, fmm_state);
+    _mav_put_uint8_t(buf, 158, dpl_state);
+    _mav_put_uint8_t(buf, 159, abk_state);
+    _mav_put_uint8_t(buf, 160, nas_state);
+    _mav_put_uint8_t(buf, 161, mea_state);
+    _mav_put_uint8_t(buf, 162, gps_fix);
+    _mav_put_uint8_t(buf, 163, pin_launch);
+    _mav_put_uint8_t(buf, 164, pin_nosecone);
+    _mav_put_uint8_t(buf, 165, pin_expulsion);
+    _mav_put_uint8_t(buf, 166, cutter_presence);
+    _mav_put_uint8_t(buf, 167, payload_can_status);
+    _mav_put_uint8_t(buf, 168, motor_can_status);
+    _mav_put_uint8_t(buf, 169, rig_can_status);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
+#else
+    mavlink_rocket_flight_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.pressure_ada = pressure_ada;
+    packet.pressure_digi = pressure_digi;
+    packet.pressure_static = pressure_static;
+    packet.pressure_dpl = pressure_dpl;
+    packet.airspeed_pitot = airspeed_pitot;
+    packet.altitude_agl = altitude_agl;
+    packet.ada_vert_speed = ada_vert_speed;
+    packet.mea_mass = mea_mass;
+    packet.acc_x = acc_x;
+    packet.acc_y = acc_y;
+    packet.acc_z = acc_z;
+    packet.gyro_x = gyro_x;
+    packet.gyro_y = gyro_y;
+    packet.gyro_z = gyro_z;
+    packet.mag_x = mag_x;
+    packet.mag_y = mag_y;
+    packet.mag_z = mag_z;
+    packet.gps_lat = gps_lat;
+    packet.gps_lon = gps_lon;
+    packet.gps_alt = gps_alt;
+    packet.abk_angle = abk_angle;
+    packet.nas_n = nas_n;
+    packet.nas_e = nas_e;
+    packet.nas_d = nas_d;
+    packet.nas_vn = nas_vn;
+    packet.nas_ve = nas_ve;
+    packet.nas_vd = nas_vd;
+    packet.nas_qx = nas_qx;
+    packet.nas_qy = nas_qy;
+    packet.nas_qz = nas_qz;
+    packet.nas_qw = nas_qw;
+    packet.nas_bias_x = nas_bias_x;
+    packet.nas_bias_y = nas_bias_y;
+    packet.nas_bias_z = nas_bias_z;
+    packet.battery_voltage = battery_voltage;
+    packet.cam_battery_voltage = cam_battery_voltage;
+    packet.temperature = temperature;
+    packet.ada_state = ada_state;
+    packet.fmm_state = fmm_state;
+    packet.dpl_state = dpl_state;
+    packet.abk_state = abk_state;
+    packet.nas_state = nas_state;
+    packet.mea_state = mea_state;
+    packet.gps_fix = gps_fix;
+    packet.pin_launch = pin_launch;
+    packet.pin_nosecone = pin_nosecone;
+    packet.pin_expulsion = pin_expulsion;
+    packet.cutter_presence = cutter_presence;
+    packet.payload_can_status = payload_can_status;
+    packet.motor_can_status = motor_can_status;
+    packet.rig_can_status = rig_can_status;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a rocket_flight_tm message on a channel
  * @param system_id ID of this system
@@ -578,6 +764,20 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_i
     return mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, chan, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->temperature, rocket_flight_tm->payload_can_status, rocket_flight_tm->motor_can_status, rocket_flight_tm->rig_can_status);
 }
 
+/**
+ * @brief Encode a rocket_flight_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param rocket_flight_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rocket_flight_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
+{
+    return mavlink_msg_rocket_flight_tm_pack_status(system_id, component_id, _status, msg,  rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->temperature, rocket_flight_tm->payload_can_status, rocket_flight_tm->motor_can_status, rocket_flight_tm->rig_can_status);
+}
+
 /**
  * @brief Send a rocket_flight_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_rocket_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_rocket_stats_tm.h
index a8a21b805bcd7b54379dbe0d67815a6463f5e3e6..7dac7049b46a9ea10a4c1e75ba798f95c6ff1bc2 100644
--- a/mavlink_lib/lyra/mavlink_msg_rocket_stats_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_rocket_stats_tm.h
@@ -183,6 +183,99 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_pack(uint8_t system_id, uint8
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
 }
 
+/**
+ * @brief Pack a rocket_stats_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param liftoff_ts [us] System clock at liftoff
+ * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
+ * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
+ * @param dpl_ts [us] System clock at drouge deployment
+ * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
+ * @param max_z_speed_ts [us] System clock at ADA max vertical speed
+ * @param max_z_speed [m/s] Max measured vertical speed - ADA
+ * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
+ * @param max_speed_altitude [m] Altitude at max speed
+ * @param apogee_ts [us] System clock at apogee
+ * @param apogee_lat [deg] Apogee latitude
+ * @param apogee_lon [deg] Apogee longitude
+ * @param apogee_alt [m] Apogee altitude
+ * @param min_pressure [Pa] Apogee pressure - Digital barometer
+ * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
+ * @param dpl_bay_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
+ * @param cpu_load  CPU load in percentage
+ * @param free_heap  Amount of available heap in memory
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param writes_failed  Number of fwrite() that failed
+ * @param hil_state  1 if the board is currently in HIL mode
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rocket_stats_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_bay_max_pressure, float cpu_load, uint32_t free_heap, int16_t log_number, int32_t writes_failed, uint8_t hil_state)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
+    _mav_put_uint64_t(buf, 0, liftoff_ts);
+    _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
+    _mav_put_uint64_t(buf, 16, dpl_ts);
+    _mav_put_uint64_t(buf, 24, max_z_speed_ts);
+    _mav_put_uint64_t(buf, 32, apogee_ts);
+    _mav_put_float(buf, 40, liftoff_max_acc);
+    _mav_put_float(buf, 44, dpl_max_acc);
+    _mav_put_float(buf, 48, max_z_speed);
+    _mav_put_float(buf, 52, max_airspeed_pitot);
+    _mav_put_float(buf, 56, max_speed_altitude);
+    _mav_put_float(buf, 60, apogee_lat);
+    _mav_put_float(buf, 64, apogee_lon);
+    _mav_put_float(buf, 68, apogee_alt);
+    _mav_put_float(buf, 72, min_pressure);
+    _mav_put_float(buf, 76, ada_min_pressure);
+    _mav_put_float(buf, 80, dpl_bay_max_pressure);
+    _mav_put_float(buf, 84, cpu_load);
+    _mav_put_uint32_t(buf, 88, free_heap);
+    _mav_put_int32_t(buf, 92, writes_failed);
+    _mav_put_int16_t(buf, 96, log_number);
+    _mav_put_uint8_t(buf, 98, hil_state);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
+#else
+    mavlink_rocket_stats_tm_t packet;
+    packet.liftoff_ts = liftoff_ts;
+    packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
+    packet.dpl_ts = dpl_ts;
+    packet.max_z_speed_ts = max_z_speed_ts;
+    packet.apogee_ts = apogee_ts;
+    packet.liftoff_max_acc = liftoff_max_acc;
+    packet.dpl_max_acc = dpl_max_acc;
+    packet.max_z_speed = max_z_speed;
+    packet.max_airspeed_pitot = max_airspeed_pitot;
+    packet.max_speed_altitude = max_speed_altitude;
+    packet.apogee_lat = apogee_lat;
+    packet.apogee_lon = apogee_lon;
+    packet.apogee_alt = apogee_alt;
+    packet.min_pressure = min_pressure;
+    packet.ada_min_pressure = ada_min_pressure;
+    packet.dpl_bay_max_pressure = dpl_bay_max_pressure;
+    packet.cpu_load = cpu_load;
+    packet.free_heap = free_heap;
+    packet.writes_failed = writes_failed;
+    packet.log_number = log_number;
+    packet.hil_state = hil_state;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ROCKET_STATS_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a rocket_stats_tm message on a channel
  * @param system_id ID of this system
@@ -299,6 +392,20 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_encode_chan(uint8_t system_id
     return mavlink_msg_rocket_stats_tm_pack_chan(system_id, component_id, chan, msg, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_bay_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap, rocket_stats_tm->log_number, rocket_stats_tm->writes_failed, rocket_stats_tm->hil_state);
 }
 
+/**
+ * @brief Encode a rocket_stats_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param rocket_stats_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rocket_stats_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
+{
+    return mavlink_msg_rocket_stats_tm_pack_status(system_id, component_id, _status, msg,  rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_bay_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap, rocket_stats_tm->log_number, rocket_stats_tm->writes_failed, rocket_stats_tm->hil_state);
+}
+
 /**
  * @brief Send a rocket_stats_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_sensor_state_tm.h b/mavlink_lib/lyra/mavlink_msg_sensor_state_tm.h
index f07dc0ac404bcf0e9a9cd927f836da2b935dbaf2..d5d5ad5015dd5a5b5b3deb0a1f9937f3b9484ad3 100644
--- a/mavlink_lib/lyra/mavlink_msg_sensor_state_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_sensor_state_tm.h
@@ -73,6 +73,43 @@ static inline uint16_t mavlink_msg_sensor_state_tm_pack(uint8_t system_id, uint8
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
 }
 
+/**
+ * @brief Pack a sensor_state_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param sensor_name  Sensor name
+ * @param initialized  Boolean that represents the init state
+ * @param enabled  Boolean that represents the enabled state
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_sensor_state_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               const char *sensor_name, uint8_t initialized, uint8_t enabled)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
+    _mav_put_uint8_t(buf, 20, initialized);
+    _mav_put_uint8_t(buf, 21, enabled);
+    _mav_put_char_array(buf, 0, sensor_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
+#else
+    mavlink_sensor_state_tm_t packet;
+    packet.initialized = initialized;
+    packet.enabled = enabled;
+    mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SENSOR_STATE_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a sensor_state_tm message on a channel
  * @param system_id ID of this system
@@ -133,6 +170,20 @@ static inline uint16_t mavlink_msg_sensor_state_tm_encode_chan(uint8_t system_id
     return mavlink_msg_sensor_state_tm_pack_chan(system_id, component_id, chan, msg, sensor_state_tm->sensor_name, sensor_state_tm->initialized, sensor_state_tm->enabled);
 }
 
+/**
+ * @brief Encode a sensor_state_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param sensor_state_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sensor_state_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_sensor_state_tm_t* sensor_state_tm)
+{
+    return mavlink_msg_sensor_state_tm_pack_status(system_id, component_id, _status, msg,  sensor_state_tm->sensor_name, sensor_state_tm->initialized, sensor_state_tm->enabled);
+}
+
 /**
  * @brief Send a sensor_state_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_sensor_tm_request_tc.h b/mavlink_lib/lyra/mavlink_msg_sensor_tm_request_tc.h
index bdf4a43617f74e9ba284ef8613ba5f01e808b707..1b08c8d75f713d3e9ce4770a3c906edb391756cd 100644
--- a/mavlink_lib/lyra/mavlink_msg_sensor_tm_request_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_sensor_tm_request_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_sensor_tm_request_tc_pack(uint8_t system_id,
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
 }
 
+/**
+ * @brief Pack a sensor_tm_request_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param sensor_name  A member of the SensorTMList enum
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_sensor_tm_request_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t sensor_name)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN];
+    _mav_put_uint8_t(buf, 0, sensor_name);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
+#else
+    mavlink_sensor_tm_request_tc_t packet;
+    packet.sensor_name = sensor_name;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a sensor_tm_request_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_sensor_tm_request_tc_encode_chan(uint8_t syst
     return mavlink_msg_sensor_tm_request_tc_pack_chan(system_id, component_id, chan, msg, sensor_tm_request_tc->sensor_name);
 }
 
+/**
+ * @brief Encode a sensor_tm_request_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param sensor_tm_request_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sensor_tm_request_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
+{
+    return mavlink_msg_sensor_tm_request_tc_pack_status(system_id, component_id, _status, msg,  sensor_tm_request_tc->sensor_name);
+}
+
 /**
  * @brief Send a sensor_tm_request_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_servo_tm.h b/mavlink_lib/lyra/mavlink_msg_servo_tm.h
index 22851b9302ca7a4c1d75e87c98afb65a54fd33c9..028462e51d3f02ecf290fcb13e9b70b506a6177d 100644
--- a/mavlink_lib/lyra/mavlink_msg_servo_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_servo_tm.h
@@ -69,6 +69,42 @@ static inline uint16_t mavlink_msg_servo_tm_pack(uint8_t system_id, uint8_t comp
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
 }
 
+/**
+ * @brief Pack a servo_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param servo_id  A member of the ServosList enum
+ * @param servo_position  Position of the servo [0-1]
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_servo_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t servo_id, float servo_position)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SERVO_TM_LEN];
+    _mav_put_float(buf, 0, servo_position);
+    _mav_put_uint8_t(buf, 4, servo_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_LEN);
+#else
+    mavlink_servo_tm_t packet;
+    packet.servo_position = servo_position;
+    packet.servo_id = servo_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SERVO_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a servo_tm message on a channel
  * @param system_id ID of this system
@@ -128,6 +164,20 @@ static inline uint16_t mavlink_msg_servo_tm_encode_chan(uint8_t system_id, uint8
     return mavlink_msg_servo_tm_pack_chan(system_id, component_id, chan, msg, servo_tm->servo_id, servo_tm->servo_position);
 }
 
+/**
+ * @brief Encode a servo_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param servo_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_servo_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_servo_tm_t* servo_tm)
+{
+    return mavlink_msg_servo_tm_pack_status(system_id, component_id, _status, msg,  servo_tm->servo_id, servo_tm->servo_position);
+}
+
 /**
  * @brief Send a servo_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_servo_tm_request_tc.h b/mavlink_lib/lyra/mavlink_msg_servo_tm_request_tc.h
index 6ac27824c3a9ac7df9d8bf0a0983c552f689cb71..f7ad30c3dd5d16d503b679edffe373dd56e3f26b 100644
--- a/mavlink_lib/lyra/mavlink_msg_servo_tm_request_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_servo_tm_request_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_servo_tm_request_tc_pack(uint8_t system_id, u
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
 }
 
+/**
+ * @brief Pack a servo_tm_request_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param servo_id  A member of the ServosList enum
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_servo_tm_request_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t servo_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN];
+    _mav_put_uint8_t(buf, 0, servo_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
+#else
+    mavlink_servo_tm_request_tc_t packet;
+    packet.servo_id = servo_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a servo_tm_request_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_servo_tm_request_tc_encode_chan(uint8_t syste
     return mavlink_msg_servo_tm_request_tc_pack_chan(system_id, component_id, chan, msg, servo_tm_request_tc->servo_id);
 }
 
+/**
+ * @brief Encode a servo_tm_request_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param servo_tm_request_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_servo_tm_request_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
+{
+    return mavlink_msg_servo_tm_request_tc_pack_status(system_id, component_id, _status, msg,  servo_tm_request_tc->servo_id);
+}
+
 /**
  * @brief Send a servo_tm_request_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_algorithm_tc.h b/mavlink_lib/lyra/mavlink_msg_set_algorithm_tc.h
index b9cbbdbd3e049a5339ed0a495302e266af2a2e88..6dc56d29b3ddc909a4e966796bf1de66a0bb4859 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_algorithm_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_algorithm_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_set_algorithm_tc_pack(uint8_t system_id, uint
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_algorithm_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param algorithm_number  Algorithm number
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_algorithm_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t algorithm_number)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN];
+    _mav_put_uint8_t(buf, 0, algorithm_number);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
+#else
+    mavlink_set_algorithm_tc_t packet;
+    packet.algorithm_number = algorithm_number;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_ALGORITHM_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_algorithm_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_set_algorithm_tc_encode_chan(uint8_t system_i
     return mavlink_msg_set_algorithm_tc_pack_chan(system_id, component_id, chan, msg, set_algorithm_tc->algorithm_number);
 }
 
+/**
+ * @brief Encode a set_algorithm_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_algorithm_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_algorithm_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_algorithm_tc_t* set_algorithm_tc)
+{
+    return mavlink_msg_set_algorithm_tc_pack_status(system_id, component_id, _status, msg,  set_algorithm_tc->algorithm_number);
+}
+
 /**
  * @brief Send a set_algorithm_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_antenna_coordinates_arp_tc.h b/mavlink_lib/lyra/mavlink_msg_set_antenna_coordinates_arp_tc.h
index 0382258bb2c3d3d81b2b96f8f060d943176d1011..c0fb1710ba50b316d988e3b076b60543063f8151 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_antenna_coordinates_arp_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_antenna_coordinates_arp_tc.h
@@ -7,15 +7,16 @@
 typedef struct __mavlink_set_antenna_coordinates_arp_tc_t {
  float latitude; /*< [deg] Latitude*/
  float longitude; /*< [deg] Longitude*/
+ float height; /*< [m] Height*/
 } mavlink_set_antenna_coordinates_arp_tc_t;
 
-#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_151_LEN 8
-#define MAVLINK_MSG_ID_151_MIN_LEN 8
+#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN 12
+#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN 12
+#define MAVLINK_MSG_ID_151_LEN 12
+#define MAVLINK_MSG_ID_151_MIN_LEN 12
 
-#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC 202
-#define MAVLINK_MSG_ID_151_CRC 202
+#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC 183
+#define MAVLINK_MSG_ID_151_CRC 183
 
 
 
@@ -23,17 +24,19 @@ typedef struct __mavlink_set_antenna_coordinates_arp_tc_t {
 #define MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC { \
     151, \
     "SET_ANTENNA_COORDINATES_ARP_TC", \
-    2, \
+    3, \
     {  { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, latitude) }, \
          { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, longitude) }, \
+         { "height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, height) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC { \
     "SET_ANTENNA_COORDINATES_ARP_TC", \
-    2, \
+    3, \
     {  { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, latitude) }, \
          { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, longitude) }, \
+         { "height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, height) }, \
          } \
 }
 #endif
@@ -46,21 +49,24 @@ typedef struct __mavlink_set_antenna_coordinates_arp_tc_t {
  *
  * @param latitude [deg] Latitude
  * @param longitude [deg] Longitude
+ * @param height [m] Height
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               float latitude, float longitude)
+                               float latitude, float longitude, float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN];
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
 #else
     mavlink_set_antenna_coordinates_arp_tc_t packet;
     packet.latitude = latitude;
     packet.longitude = longitude;
+    packet.height = height;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
 #endif
@@ -69,6 +75,45 @@ static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_pack(uint8_t s
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_antenna_coordinates_arp_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param latitude [deg] Latitude
+ * @param longitude [deg] Longitude
+ * @param height [m] Height
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               float latitude, float longitude, float height)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN];
+    _mav_put_float(buf, 0, latitude);
+    _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
+#else
+    mavlink_set_antenna_coordinates_arp_tc_t packet;
+    packet.latitude = latitude;
+    packet.longitude = longitude;
+    packet.height = height;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_antenna_coordinates_arp_tc message on a channel
  * @param system_id ID of this system
@@ -77,22 +122,25 @@ static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_pack(uint8_t s
  * @param msg The MAVLink message to compress the data into
  * @param latitude [deg] Latitude
  * @param longitude [deg] Longitude
+ * @param height [m] Height
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   float latitude,float longitude)
+                                   float latitude,float longitude,float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN];
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
 #else
     mavlink_set_antenna_coordinates_arp_tc_t packet;
     packet.latitude = latitude;
     packet.longitude = longitude;
+    packet.height = height;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
 #endif
@@ -111,7 +159,7 @@ static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(uint
  */
 static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_antenna_coordinates_arp_tc_t* set_antenna_coordinates_arp_tc)
 {
-    return mavlink_msg_set_antenna_coordinates_arp_tc_pack(system_id, component_id, msg, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude);
+    return mavlink_msg_set_antenna_coordinates_arp_tc_pack(system_id, component_id, msg, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude, set_antenna_coordinates_arp_tc->height);
 }
 
 /**
@@ -125,7 +173,21 @@ static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_encode(uint8_t
  */
 static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_antenna_coordinates_arp_tc_t* set_antenna_coordinates_arp_tc)
 {
-    return mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(system_id, component_id, chan, msg, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude);
+    return mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(system_id, component_id, chan, msg, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude, set_antenna_coordinates_arp_tc->height);
+}
+
+/**
+ * @brief Encode a set_antenna_coordinates_arp_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_antenna_coordinates_arp_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_antenna_coordinates_arp_tc_t* set_antenna_coordinates_arp_tc)
+{
+    return mavlink_msg_set_antenna_coordinates_arp_tc_pack_status(system_id, component_id, _status, msg,  set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude, set_antenna_coordinates_arp_tc->height);
 }
 
 /**
@@ -134,21 +196,24 @@ static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_encode_chan(ui
  *
  * @param latitude [deg] Latitude
  * @param longitude [deg] Longitude
+ * @param height [m] Height
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send(mavlink_channel_t chan, float latitude, float longitude)
+static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send(mavlink_channel_t chan, float latitude, float longitude, float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN];
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
 #else
     mavlink_set_antenna_coordinates_arp_tc_t packet;
     packet.latitude = latitude;
     packet.longitude = longitude;
+    packet.height = height;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
 #endif
@@ -162,7 +227,7 @@ static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send(mavlink_chann
 static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send_struct(mavlink_channel_t chan, const mavlink_set_antenna_coordinates_arp_tc_t* set_antenna_coordinates_arp_tc)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_set_antenna_coordinates_arp_tc_send(chan, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude);
+    mavlink_msg_set_antenna_coordinates_arp_tc_send(chan, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude, set_antenna_coordinates_arp_tc->height);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, (const char *)set_antenna_coordinates_arp_tc, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
 #endif
@@ -176,18 +241,20 @@ static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send_struct(mavlin
   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_set_antenna_coordinates_arp_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  float latitude, float longitude)
+static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  float latitude, float longitude, float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
 #else
     mavlink_set_antenna_coordinates_arp_tc_t *packet = (mavlink_set_antenna_coordinates_arp_tc_t *)msgbuf;
     packet->latitude = latitude;
     packet->longitude = longitude;
+    packet->height = height;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
 #endif
@@ -219,6 +286,16 @@ static inline float mavlink_msg_set_antenna_coordinates_arp_tc_get_longitude(con
     return _MAV_RETURN_float(msg,  4);
 }
 
+/**
+ * @brief Get field height from set_antenna_coordinates_arp_tc message
+ *
+ * @return [m] Height
+ */
+static inline float mavlink_msg_set_antenna_coordinates_arp_tc_get_height(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  8);
+}
+
 /**
  * @brief Decode a set_antenna_coordinates_arp_tc message into a struct
  *
@@ -230,6 +307,7 @@ static inline void mavlink_msg_set_antenna_coordinates_arp_tc_decode(const mavli
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     set_antenna_coordinates_arp_tc->latitude = mavlink_msg_set_antenna_coordinates_arp_tc_get_latitude(msg);
     set_antenna_coordinates_arp_tc->longitude = mavlink_msg_set_antenna_coordinates_arp_tc_get_longitude(msg);
+    set_antenna_coordinates_arp_tc->height = mavlink_msg_set_antenna_coordinates_arp_tc_get_height(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN;
         memset(set_antenna_coordinates_arp_tc, 0, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_set_atomic_valve_timing_tc.h b/mavlink_lib/lyra/mavlink_msg_set_atomic_valve_timing_tc.h
index c43a37eaf41e0d36febf5349e3461b43720d51f5..1c4565c6e12c27fd4c0f961452487771e2a8702c 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_atomic_valve_timing_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_atomic_valve_timing_tc.h
@@ -69,6 +69,42 @@ static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_pack(uint8_t syste
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_atomic_valve_timing_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param servo_id  A member of the ServosList enum
+ * @param maximum_timing [ms] Maximum timing in [ms]
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t servo_id, uint32_t maximum_timing)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN];
+    _mav_put_uint32_t(buf, 0, maximum_timing);
+    _mav_put_uint8_t(buf, 4, servo_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
+#else
+    mavlink_set_atomic_valve_timing_tc_t packet;
+    packet.maximum_timing = maximum_timing;
+    packet.servo_id = servo_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_atomic_valve_timing_tc message on a channel
  * @param system_id ID of this system
@@ -128,6 +164,20 @@ static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_encode_chan(uint8_
     return mavlink_msg_set_atomic_valve_timing_tc_pack_chan(system_id, component_id, chan, msg, set_atomic_valve_timing_tc->servo_id, set_atomic_valve_timing_tc->maximum_timing);
 }
 
+/**
+ * @brief Encode a set_atomic_valve_timing_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_atomic_valve_timing_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_atomic_valve_timing_tc_t* set_atomic_valve_timing_tc)
+{
+    return mavlink_msg_set_atomic_valve_timing_tc_pack_status(system_id, component_id, _status, msg,  set_atomic_valve_timing_tc->servo_id, set_atomic_valve_timing_tc->maximum_timing);
+}
+
 /**
  * @brief Send a set_atomic_valve_timing_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_cooling_time_tc.h b/mavlink_lib/lyra/mavlink_msg_set_cooling_time_tc.h
index ca49e31c787b7af30cfeed5d599e610a27acc00a..78c1d81c761f637436b26b9bef50f9cef72643a3 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_cooling_time_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_cooling_time_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_set_cooling_time_tc_pack(uint8_t system_id, u
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_COOLING_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COOLING_TIME_TC_LEN, MAVLINK_MSG_ID_SET_COOLING_TIME_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_cooling_time_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timing [ms] Timing in [ms]
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_cooling_time_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint32_t timing)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_COOLING_TIME_TC_LEN];
+    _mav_put_uint32_t(buf, 0, timing);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_COOLING_TIME_TC_LEN);
+#else
+    mavlink_set_cooling_time_tc_t packet;
+    packet.timing = timing;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_COOLING_TIME_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_COOLING_TIME_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_COOLING_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COOLING_TIME_TC_LEN, MAVLINK_MSG_ID_SET_COOLING_TIME_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_COOLING_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COOLING_TIME_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_cooling_time_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_set_cooling_time_tc_encode_chan(uint8_t syste
     return mavlink_msg_set_cooling_time_tc_pack_chan(system_id, component_id, chan, msg, set_cooling_time_tc->timing);
 }
 
+/**
+ * @brief Encode a set_cooling_time_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_cooling_time_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_cooling_time_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_cooling_time_tc_t* set_cooling_time_tc)
+{
+    return mavlink_msg_set_cooling_time_tc_pack_status(system_id, component_id, _status, msg,  set_cooling_time_tc->timing);
+}
+
 /**
  * @brief Send a set_cooling_time_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_coordinates_tc.h b/mavlink_lib/lyra/mavlink_msg_set_coordinates_tc.h
index dd9f914ee780beca86428061f55fa1835510b840..606d035bdebc3b5cb86b265ff8e1edfe66f61c66 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_coordinates_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_coordinates_tc.h
@@ -69,6 +69,42 @@ static inline uint16_t mavlink_msg_set_coordinates_tc_pack(uint8_t system_id, ui
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_coordinates_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param latitude [deg] Latitude
+ * @param longitude [deg] Longitude
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_coordinates_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               float latitude, float longitude)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN];
+    _mav_put_float(buf, 0, latitude);
+    _mav_put_float(buf, 4, longitude);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
+#else
+    mavlink_set_coordinates_tc_t packet;
+    packet.latitude = latitude;
+    packet.longitude = longitude;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_COORDINATES_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_coordinates_tc message on a channel
  * @param system_id ID of this system
@@ -128,6 +164,20 @@ static inline uint16_t mavlink_msg_set_coordinates_tc_encode_chan(uint8_t system
     return mavlink_msg_set_coordinates_tc_pack_chan(system_id, component_id, chan, msg, set_coordinates_tc->latitude, set_coordinates_tc->longitude);
 }
 
+/**
+ * @brief Encode a set_coordinates_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_coordinates_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_coordinates_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_coordinates_tc_t* set_coordinates_tc)
+{
+    return mavlink_msg_set_coordinates_tc_pack_status(system_id, component_id, _status, msg,  set_coordinates_tc->latitude, set_coordinates_tc->longitude);
+}
+
 /**
  * @brief Send a set_coordinates_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_deployment_altitude_tc.h b/mavlink_lib/lyra/mavlink_msg_set_deployment_altitude_tc.h
index c8ab791c2fcc1eae10513251650426b28c7756c6..fd4da604912a9d02f3e7924454801b2643849f45 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_deployment_altitude_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_deployment_altitude_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_set_deployment_altitude_tc_pack(uint8_t syste
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_deployment_altitude_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param dpl_altitude [m] Deployment altitude
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_deployment_altitude_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               float dpl_altitude)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
+    _mav_put_float(buf, 0, dpl_altitude);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
+#else
+    mavlink_set_deployment_altitude_tc_t packet;
+    packet.dpl_altitude = dpl_altitude;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_deployment_altitude_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_set_deployment_altitude_tc_encode_chan(uint8_
     return mavlink_msg_set_deployment_altitude_tc_pack_chan(system_id, component_id, chan, msg, set_deployment_altitude_tc->dpl_altitude);
 }
 
+/**
+ * @brief Encode a set_deployment_altitude_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_deployment_altitude_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_deployment_altitude_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
+{
+    return mavlink_msg_set_deployment_altitude_tc_pack_status(system_id, component_id, _status, msg,  set_deployment_altitude_tc->dpl_altitude);
+}
+
 /**
  * @brief Send a set_deployment_altitude_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_ignition_time_tc.h b/mavlink_lib/lyra/mavlink_msg_set_ignition_time_tc.h
index 43354ed53ff5e0cc6a19f2f26d4c9937b89d7fed..b6be34a12cd42150da584d8ba6ac94f0de467f9e 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_ignition_time_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_ignition_time_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_set_ignition_time_tc_pack(uint8_t system_id,
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_ignition_time_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timing [ms] Timing in [ms]
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_ignition_time_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint32_t timing)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN];
+    _mav_put_uint32_t(buf, 0, timing);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
+#else
+    mavlink_set_ignition_time_tc_t packet;
+    packet.timing = timing;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_IGNITION_TIME_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_ignition_time_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_set_ignition_time_tc_encode_chan(uint8_t syst
     return mavlink_msg_set_ignition_time_tc_pack_chan(system_id, component_id, chan, msg, set_ignition_time_tc->timing);
 }
 
+/**
+ * @brief Encode a set_ignition_time_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_ignition_time_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_ignition_time_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_ignition_time_tc_t* set_ignition_time_tc)
+{
+    return mavlink_msg_set_ignition_time_tc_pack_status(system_id, component_id, _status, msg,  set_ignition_time_tc->timing);
+}
+
 /**
  * @brief Send a set_ignition_time_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_nitrogen_time_tc.h b/mavlink_lib/lyra/mavlink_msg_set_nitrogen_time_tc.h
index 49ed042bde281bd1d8828abcf237a66197c7eb7d..b132a40b3340a349d019f336a9fc341184809ce3 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_nitrogen_time_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_nitrogen_time_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_set_nitrogen_time_tc_pack(uint8_t system_id,
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_LEN, MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_nitrogen_time_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timing [ms] Timing in [ms]
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_nitrogen_time_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint32_t timing)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_LEN];
+    _mav_put_uint32_t(buf, 0, timing);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_LEN);
+#else
+    mavlink_set_nitrogen_time_tc_t packet;
+    packet.timing = timing;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_LEN, MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_nitrogen_time_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_set_nitrogen_time_tc_encode_chan(uint8_t syst
     return mavlink_msg_set_nitrogen_time_tc_pack_chan(system_id, component_id, chan, msg, set_nitrogen_time_tc->timing);
 }
 
+/**
+ * @brief Encode a set_nitrogen_time_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_nitrogen_time_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_nitrogen_time_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_nitrogen_time_tc_t* set_nitrogen_time_tc)
+{
+    return mavlink_msg_set_nitrogen_time_tc_pack_status(system_id, component_id, _status, msg,  set_nitrogen_time_tc->timing);
+}
+
 /**
  * @brief Send a set_nitrogen_time_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_orientation_quat_tc.h b/mavlink_lib/lyra/mavlink_msg_set_orientation_quat_tc.h
index fefd5c712166669dfaca1a1ff45aa1581da5ee59..07a5ac874eafba08de8dd448bbb5a900b3557312 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_orientation_quat_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_orientation_quat_tc.h
@@ -81,6 +81,48 @@ static inline uint16_t mavlink_msg_set_orientation_quat_tc_pack(uint8_t system_i
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_orientation_quat_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param quat_x  Quaternion x component
+ * @param quat_y  Quaternion y component
+ * @param quat_z  Quaternion z component
+ * @param quat_w  Quaternion w component
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_orientation_quat_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               float quat_x, float quat_y, float quat_z, float quat_w)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN];
+    _mav_put_float(buf, 0, quat_x);
+    _mav_put_float(buf, 4, quat_y);
+    _mav_put_float(buf, 8, quat_z);
+    _mav_put_float(buf, 12, quat_w);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN);
+#else
+    mavlink_set_orientation_quat_tc_t packet;
+    packet.quat_x = quat_x;
+    packet.quat_y = quat_y;
+    packet.quat_z = quat_z;
+    packet.quat_w = quat_w;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_orientation_quat_tc message on a channel
  * @param system_id ID of this system
@@ -146,6 +188,20 @@ static inline uint16_t mavlink_msg_set_orientation_quat_tc_encode_chan(uint8_t s
     return mavlink_msg_set_orientation_quat_tc_pack_chan(system_id, component_id, chan, msg, set_orientation_quat_tc->quat_x, set_orientation_quat_tc->quat_y, set_orientation_quat_tc->quat_z, set_orientation_quat_tc->quat_w);
 }
 
+/**
+ * @brief Encode a set_orientation_quat_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_orientation_quat_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_orientation_quat_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_orientation_quat_tc_t* set_orientation_quat_tc)
+{
+    return mavlink_msg_set_orientation_quat_tc_pack_status(system_id, component_id, _status, msg,  set_orientation_quat_tc->quat_x, set_orientation_quat_tc->quat_y, set_orientation_quat_tc->quat_z, set_orientation_quat_tc->quat_w);
+}
+
 /**
  * @brief Send a set_orientation_quat_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_orientation_tc.h b/mavlink_lib/lyra/mavlink_msg_set_orientation_tc.h
index 5169814cd4c7a7afbe6e204bf82fb2d049078fc7..6b40eb07ac6b25f5873b7ad9801961c7ed148e10 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_orientation_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_orientation_tc.h
@@ -75,6 +75,45 @@ static inline uint16_t mavlink_msg_set_orientation_tc_pack(uint8_t system_id, ui
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_orientation_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param yaw [deg] Yaw angle
+ * @param pitch [deg] Pitch angle
+ * @param roll [deg] Roll angle
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_orientation_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               float yaw, float pitch, float roll)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN];
+    _mav_put_float(buf, 0, yaw);
+    _mav_put_float(buf, 4, pitch);
+    _mav_put_float(buf, 8, roll);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
+#else
+    mavlink_set_orientation_tc_t packet;
+    packet.yaw = yaw;
+    packet.pitch = pitch;
+    packet.roll = roll;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_ORIENTATION_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_orientation_tc message on a channel
  * @param system_id ID of this system
@@ -137,6 +176,20 @@ static inline uint16_t mavlink_msg_set_orientation_tc_encode_chan(uint8_t system
     return mavlink_msg_set_orientation_tc_pack_chan(system_id, component_id, chan, msg, set_orientation_tc->yaw, set_orientation_tc->pitch, set_orientation_tc->roll);
 }
 
+/**
+ * @brief Encode a set_orientation_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_orientation_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_orientation_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_orientation_tc_t* set_orientation_tc)
+{
+    return mavlink_msg_set_orientation_tc_pack_status(system_id, component_id, _status, msg,  set_orientation_tc->yaw, set_orientation_tc->pitch, set_orientation_tc->roll);
+}
+
 /**
  * @brief Send a set_orientation_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_reference_altitude_tc.h b/mavlink_lib/lyra/mavlink_msg_set_reference_altitude_tc.h
index a291b0b8da0d1d60e7e30767ade22abc5f35402a..710d27b5feb727b0ad8fd5e26a92ed52d0fef728 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_reference_altitude_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_reference_altitude_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_set_reference_altitude_tc_pack(uint8_t system
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_reference_altitude_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param ref_altitude [m] Reference altitude
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_reference_altitude_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               float ref_altitude)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN];
+    _mav_put_float(buf, 0, ref_altitude);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
+#else
+    mavlink_set_reference_altitude_tc_t packet;
+    packet.ref_altitude = ref_altitude;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_reference_altitude_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_set_reference_altitude_tc_encode_chan(uint8_t
     return mavlink_msg_set_reference_altitude_tc_pack_chan(system_id, component_id, chan, msg, set_reference_altitude_tc->ref_altitude);
 }
 
+/**
+ * @brief Encode a set_reference_altitude_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_reference_altitude_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_reference_altitude_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
+{
+    return mavlink_msg_set_reference_altitude_tc_pack_status(system_id, component_id, _status, msg,  set_reference_altitude_tc->ref_altitude);
+}
+
 /**
  * @brief Send a set_reference_altitude_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_reference_temperature_tc.h b/mavlink_lib/lyra/mavlink_msg_set_reference_temperature_tc.h
index 5bb1c529477606617b93eca65726e9580259f832..4a6f840a89125e2f31064a4745790aff4e6ce345 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_reference_temperature_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_reference_temperature_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_set_reference_temperature_tc_pack(uint8_t sys
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_reference_temperature_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param ref_temp [degC] Reference temperature
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_reference_temperature_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               float ref_temp)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
+    _mav_put_float(buf, 0, ref_temp);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
+#else
+    mavlink_set_reference_temperature_tc_t packet;
+    packet.ref_temp = ref_temp;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_reference_temperature_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_set_reference_temperature_tc_encode_chan(uint
     return mavlink_msg_set_reference_temperature_tc_pack_chan(system_id, component_id, chan, msg, set_reference_temperature_tc->ref_temp);
 }
 
+/**
+ * @brief Encode a set_reference_temperature_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_reference_temperature_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_reference_temperature_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
+{
+    return mavlink_msg_set_reference_temperature_tc_pack_status(system_id, component_id, _status, msg,  set_reference_temperature_tc->ref_temp);
+}
+
 /**
  * @brief Send a set_reference_temperature_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_rocket_coordinates_arp_tc.h b/mavlink_lib/lyra/mavlink_msg_set_rocket_coordinates_arp_tc.h
index 30b889acfa330f98ac9004c67c4b47b961b07356..6998448e7aaa36fa8715a257b19e9bc854de0820 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_rocket_coordinates_arp_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_rocket_coordinates_arp_tc.h
@@ -7,15 +7,16 @@
 typedef struct __mavlink_set_rocket_coordinates_arp_tc_t {
  float latitude; /*< [deg] Latitude*/
  float longitude; /*< [deg] Longitude*/
+ float height; /*< [m] Height*/
 } mavlink_set_rocket_coordinates_arp_tc_t;
 
-#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_152_LEN 8
-#define MAVLINK_MSG_ID_152_MIN_LEN 8
+#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN 12
+#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN 12
+#define MAVLINK_MSG_ID_152_LEN 12
+#define MAVLINK_MSG_ID_152_MIN_LEN 12
 
-#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC 164
-#define MAVLINK_MSG_ID_152_CRC 164
+#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC 220
+#define MAVLINK_MSG_ID_152_CRC 220
 
 
 
@@ -23,17 +24,19 @@ typedef struct __mavlink_set_rocket_coordinates_arp_tc_t {
 #define MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC { \
     152, \
     "SET_ROCKET_COORDINATES_ARP_TC", \
-    2, \
+    3, \
     {  { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, latitude) }, \
          { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, longitude) }, \
+         { "height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, height) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC { \
     "SET_ROCKET_COORDINATES_ARP_TC", \
-    2, \
+    3, \
     {  { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, latitude) }, \
          { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, longitude) }, \
+         { "height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, height) }, \
          } \
 }
 #endif
@@ -46,21 +49,24 @@ typedef struct __mavlink_set_rocket_coordinates_arp_tc_t {
  *
  * @param latitude [deg] Latitude
  * @param longitude [deg] Longitude
+ * @param height [m] Height
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               float latitude, float longitude)
+                               float latitude, float longitude, float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN];
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
 #else
     mavlink_set_rocket_coordinates_arp_tc_t packet;
     packet.latitude = latitude;
     packet.longitude = longitude;
+    packet.height = height;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
 #endif
@@ -69,6 +75,45 @@ static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_pack(uint8_t sy
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_rocket_coordinates_arp_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param latitude [deg] Latitude
+ * @param longitude [deg] Longitude
+ * @param height [m] Height
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               float latitude, float longitude, float height)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN];
+    _mav_put_float(buf, 0, latitude);
+    _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
+#else
+    mavlink_set_rocket_coordinates_arp_tc_t packet;
+    packet.latitude = latitude;
+    packet.longitude = longitude;
+    packet.height = height;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_rocket_coordinates_arp_tc message on a channel
  * @param system_id ID of this system
@@ -77,22 +122,25 @@ static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_pack(uint8_t sy
  * @param msg The MAVLink message to compress the data into
  * @param latitude [deg] Latitude
  * @param longitude [deg] Longitude
+ * @param height [m] Height
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   float latitude,float longitude)
+                                   float latitude,float longitude,float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN];
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
 #else
     mavlink_set_rocket_coordinates_arp_tc_t packet;
     packet.latitude = latitude;
     packet.longitude = longitude;
+    packet.height = height;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
 #endif
@@ -111,7 +159,7 @@ static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(uint8
  */
 static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_rocket_coordinates_arp_tc_t* set_rocket_coordinates_arp_tc)
 {
-    return mavlink_msg_set_rocket_coordinates_arp_tc_pack(system_id, component_id, msg, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude);
+    return mavlink_msg_set_rocket_coordinates_arp_tc_pack(system_id, component_id, msg, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude, set_rocket_coordinates_arp_tc->height);
 }
 
 /**
@@ -125,7 +173,21 @@ static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_encode(uint8_t
  */
 static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_rocket_coordinates_arp_tc_t* set_rocket_coordinates_arp_tc)
 {
-    return mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(system_id, component_id, chan, msg, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude);
+    return mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(system_id, component_id, chan, msg, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude, set_rocket_coordinates_arp_tc->height);
+}
+
+/**
+ * @brief Encode a set_rocket_coordinates_arp_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_rocket_coordinates_arp_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_rocket_coordinates_arp_tc_t* set_rocket_coordinates_arp_tc)
+{
+    return mavlink_msg_set_rocket_coordinates_arp_tc_pack_status(system_id, component_id, _status, msg,  set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude, set_rocket_coordinates_arp_tc->height);
 }
 
 /**
@@ -134,21 +196,24 @@ static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_encode_chan(uin
  *
  * @param latitude [deg] Latitude
  * @param longitude [deg] Longitude
+ * @param height [m] Height
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send(mavlink_channel_t chan, float latitude, float longitude)
+static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send(mavlink_channel_t chan, float latitude, float longitude, float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN];
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
 #else
     mavlink_set_rocket_coordinates_arp_tc_t packet;
     packet.latitude = latitude;
     packet.longitude = longitude;
+    packet.height = height;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
 #endif
@@ -162,7 +227,7 @@ static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send(mavlink_channe
 static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send_struct(mavlink_channel_t chan, const mavlink_set_rocket_coordinates_arp_tc_t* set_rocket_coordinates_arp_tc)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_set_rocket_coordinates_arp_tc_send(chan, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude);
+    mavlink_msg_set_rocket_coordinates_arp_tc_send(chan, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude, set_rocket_coordinates_arp_tc->height);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, (const char *)set_rocket_coordinates_arp_tc, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
 #endif
@@ -176,18 +241,20 @@ static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send_struct(mavlink
   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_set_rocket_coordinates_arp_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  float latitude, float longitude)
+static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  float latitude, float longitude, float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
 #else
     mavlink_set_rocket_coordinates_arp_tc_t *packet = (mavlink_set_rocket_coordinates_arp_tc_t *)msgbuf;
     packet->latitude = latitude;
     packet->longitude = longitude;
+    packet->height = height;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
 #endif
@@ -219,6 +286,16 @@ static inline float mavlink_msg_set_rocket_coordinates_arp_tc_get_longitude(cons
     return _MAV_RETURN_float(msg,  4);
 }
 
+/**
+ * @brief Get field height from set_rocket_coordinates_arp_tc message
+ *
+ * @return [m] Height
+ */
+static inline float mavlink_msg_set_rocket_coordinates_arp_tc_get_height(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  8);
+}
+
 /**
  * @brief Decode a set_rocket_coordinates_arp_tc message into a struct
  *
@@ -230,6 +307,7 @@ static inline void mavlink_msg_set_rocket_coordinates_arp_tc_decode(const mavlin
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     set_rocket_coordinates_arp_tc->latitude = mavlink_msg_set_rocket_coordinates_arp_tc_get_latitude(msg);
     set_rocket_coordinates_arp_tc->longitude = mavlink_msg_set_rocket_coordinates_arp_tc_get_longitude(msg);
+    set_rocket_coordinates_arp_tc->height = mavlink_msg_set_rocket_coordinates_arp_tc_get_height(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN;
         memset(set_rocket_coordinates_arp_tc, 0, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_set_servo_angle_tc.h b/mavlink_lib/lyra/mavlink_msg_set_servo_angle_tc.h
index 74f2888721a7ed79d479df991d640deb064d50cc..350ac5444f2793052912190d783885e8842fab4d 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_servo_angle_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_servo_angle_tc.h
@@ -69,6 +69,42 @@ static inline uint16_t mavlink_msg_set_servo_angle_tc_pack(uint8_t system_id, ui
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_servo_angle_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param servo_id  A member of the ServosList enum
+ * @param angle  Servo angle in normalized value [0-1]
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_servo_angle_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t servo_id, float angle)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN];
+    _mav_put_float(buf, 0, angle);
+    _mav_put_uint8_t(buf, 4, servo_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
+#else
+    mavlink_set_servo_angle_tc_t packet;
+    packet.angle = angle;
+    packet.servo_id = servo_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_servo_angle_tc message on a channel
  * @param system_id ID of this system
@@ -128,6 +164,20 @@ static inline uint16_t mavlink_msg_set_servo_angle_tc_encode_chan(uint8_t system
     return mavlink_msg_set_servo_angle_tc_pack_chan(system_id, component_id, chan, msg, set_servo_angle_tc->servo_id, set_servo_angle_tc->angle);
 }
 
+/**
+ * @brief Encode a set_servo_angle_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_servo_angle_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_servo_angle_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
+{
+    return mavlink_msg_set_servo_angle_tc_pack_status(system_id, component_id, _status, msg,  set_servo_angle_tc->servo_id, set_servo_angle_tc->angle);
+}
+
 /**
  * @brief Send a set_servo_angle_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_stepper_angle_tc.h b/mavlink_lib/lyra/mavlink_msg_set_stepper_angle_tc.h
index 7850e94093721c50cfc9a775568ff7337e785db7..ffc19f57caf0f85728754e47fed0937f7bfeb152 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_stepper_angle_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_stepper_angle_tc.h
@@ -69,6 +69,42 @@ static inline uint16_t mavlink_msg_set_stepper_angle_tc_pack(uint8_t system_id,
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_stepper_angle_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param stepper_id  A member of the StepperList enum
+ * @param angle  Stepper angle in degrees
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_stepper_angle_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t stepper_id, float angle)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN];
+    _mav_put_float(buf, 0, angle);
+    _mav_put_uint8_t(buf, 4, stepper_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN);
+#else
+    mavlink_set_stepper_angle_tc_t packet;
+    packet.angle = angle;
+    packet.stepper_id = stepper_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_stepper_angle_tc message on a channel
  * @param system_id ID of this system
@@ -128,6 +164,20 @@ static inline uint16_t mavlink_msg_set_stepper_angle_tc_encode_chan(uint8_t syst
     return mavlink_msg_set_stepper_angle_tc_pack_chan(system_id, component_id, chan, msg, set_stepper_angle_tc->stepper_id, set_stepper_angle_tc->angle);
 }
 
+/**
+ * @brief Encode a set_stepper_angle_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_stepper_angle_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_stepper_angle_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_stepper_angle_tc_t* set_stepper_angle_tc)
+{
+    return mavlink_msg_set_stepper_angle_tc_pack_status(system_id, component_id, _status, msg,  set_stepper_angle_tc->stepper_id, set_stepper_angle_tc->angle);
+}
+
 /**
  * @brief Send a set_stepper_angle_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_stepper_steps_tc.h b/mavlink_lib/lyra/mavlink_msg_set_stepper_steps_tc.h
index 863b69612c9411bc391b21bb3b5ec31fcf532e5b..6620d8965c938960365269815bd59603e330961d 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_stepper_steps_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_stepper_steps_tc.h
@@ -69,6 +69,42 @@ static inline uint16_t mavlink_msg_set_stepper_steps_tc_pack(uint8_t system_id,
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_stepper_steps_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param stepper_id  A member of the StepperList enum
+ * @param steps  Number of steps
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_stepper_steps_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t stepper_id, float steps)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN];
+    _mav_put_float(buf, 0, steps);
+    _mav_put_uint8_t(buf, 4, stepper_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN);
+#else
+    mavlink_set_stepper_steps_tc_t packet;
+    packet.steps = steps;
+    packet.stepper_id = stepper_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_stepper_steps_tc message on a channel
  * @param system_id ID of this system
@@ -128,6 +164,20 @@ static inline uint16_t mavlink_msg_set_stepper_steps_tc_encode_chan(uint8_t syst
     return mavlink_msg_set_stepper_steps_tc_pack_chan(system_id, component_id, chan, msg, set_stepper_steps_tc->stepper_id, set_stepper_steps_tc->steps);
 }
 
+/**
+ * @brief Encode a set_stepper_steps_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_stepper_steps_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_stepper_steps_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_stepper_steps_tc_t* set_stepper_steps_tc)
+{
+    return mavlink_msg_set_stepper_steps_tc_pack_status(system_id, component_id, _status, msg,  set_stepper_steps_tc->stepper_id, set_stepper_steps_tc->steps);
+}
+
 /**
  * @brief Send a set_stepper_steps_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_target_coordinates_tc.h b/mavlink_lib/lyra/mavlink_msg_set_target_coordinates_tc.h
index 7b7b2cd06cf1404af2933543c3bf45dd00b66072..9d502cd69dcf0f5abd3a0f64a52656dc010a5d24 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_target_coordinates_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_target_coordinates_tc.h
@@ -69,6 +69,42 @@ static inline uint16_t mavlink_msg_set_target_coordinates_tc_pack(uint8_t system
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_target_coordinates_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param latitude [deg] Latitude
+ * @param longitude [deg] Longitude
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_target_coordinates_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               float latitude, float longitude)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN];
+    _mav_put_float(buf, 0, latitude);
+    _mav_put_float(buf, 4, longitude);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
+#else
+    mavlink_set_target_coordinates_tc_t packet;
+    packet.latitude = latitude;
+    packet.longitude = longitude;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_target_coordinates_tc message on a channel
  * @param system_id ID of this system
@@ -128,6 +164,20 @@ static inline uint16_t mavlink_msg_set_target_coordinates_tc_encode_chan(uint8_t
     return mavlink_msg_set_target_coordinates_tc_pack_chan(system_id, component_id, chan, msg, set_target_coordinates_tc->latitude, set_target_coordinates_tc->longitude);
 }
 
+/**
+ * @brief Encode a set_target_coordinates_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_target_coordinates_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_target_coordinates_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
+{
+    return mavlink_msg_set_target_coordinates_tc_pack_status(system_id, component_id, _status, msg,  set_target_coordinates_tc->latitude, set_target_coordinates_tc->longitude);
+}
+
 /**
  * @brief Send a set_target_coordinates_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_set_valve_maximum_aperture_tc.h b/mavlink_lib/lyra/mavlink_msg_set_valve_maximum_aperture_tc.h
index a29774f98af65e6c8981a896b79cc4c9bcc42574..722e7485c3ceea9c076ce57119a93665e1360ea8 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_valve_maximum_aperture_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_valve_maximum_aperture_tc.h
@@ -69,6 +69,42 @@ static inline uint16_t mavlink_msg_set_valve_maximum_aperture_tc_pack(uint8_t sy
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
 }
 
+/**
+ * @brief Pack a set_valve_maximum_aperture_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param servo_id  A member of the ServosList enum
+ * @param maximum_aperture  Maximum aperture
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_valve_maximum_aperture_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t servo_id, float maximum_aperture)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN];
+    _mav_put_float(buf, 0, maximum_aperture);
+    _mav_put_uint8_t(buf, 4, servo_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
+#else
+    mavlink_set_valve_maximum_aperture_tc_t packet;
+    packet.maximum_aperture = maximum_aperture;
+    packet.servo_id = servo_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a set_valve_maximum_aperture_tc message on a channel
  * @param system_id ID of this system
@@ -128,6 +164,20 @@ static inline uint16_t mavlink_msg_set_valve_maximum_aperture_tc_encode_chan(uin
     return mavlink_msg_set_valve_maximum_aperture_tc_pack_chan(system_id, component_id, chan, msg, set_valve_maximum_aperture_tc->servo_id, set_valve_maximum_aperture_tc->maximum_aperture);
 }
 
+/**
+ * @brief Encode a set_valve_maximum_aperture_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param set_valve_maximum_aperture_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_valve_maximum_aperture_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_valve_maximum_aperture_tc_t* set_valve_maximum_aperture_tc)
+{
+    return mavlink_msg_set_valve_maximum_aperture_tc_pack_status(system_id, component_id, _status, msg,  set_valve_maximum_aperture_tc->servo_id, set_valve_maximum_aperture_tc->maximum_aperture);
+}
+
 /**
  * @brief Send a set_valve_maximum_aperture_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_sys_tm.h b/mavlink_lib/lyra/mavlink_msg_sys_tm.h
index 4bbfdfedc17a6fc46c7120e2b3ff66956407e676..a17ba85596fbefb44cd05162de5c665ed2b9ccfe 100644
--- a/mavlink_lib/lyra/mavlink_msg_sys_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_sys_tm.h
@@ -111,6 +111,63 @@ static inline uint16_t mavlink_msg_sys_tm_pack(uint8_t system_id, uint8_t compon
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
 }
 
+/**
+ * @brief Pack a sys_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp
+ * @param logger  True if the logger started correctly
+ * @param event_broker  True if the event broker started correctly
+ * @param radio  True if the radio started correctly
+ * @param sensors  True if the sensors started correctly
+ * @param actuators  True if the sensors started correctly
+ * @param pin_handler  True if the pin observer started correctly
+ * @param can_handler  True if the can handler started correctly
+ * @param scheduler  True if the board scheduler is running
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_sys_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t sensors, uint8_t actuators, uint8_t pin_handler, uint8_t can_handler, uint8_t scheduler)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint8_t(buf, 8, logger);
+    _mav_put_uint8_t(buf, 9, event_broker);
+    _mav_put_uint8_t(buf, 10, radio);
+    _mav_put_uint8_t(buf, 11, sensors);
+    _mav_put_uint8_t(buf, 12, actuators);
+    _mav_put_uint8_t(buf, 13, pin_handler);
+    _mav_put_uint8_t(buf, 14, can_handler);
+    _mav_put_uint8_t(buf, 15, scheduler);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
+#else
+    mavlink_sys_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.logger = logger;
+    packet.event_broker = event_broker;
+    packet.radio = radio;
+    packet.sensors = sensors;
+    packet.actuators = actuators;
+    packet.pin_handler = pin_handler;
+    packet.can_handler = can_handler;
+    packet.scheduler = scheduler;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SYS_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a sys_tm message on a channel
  * @param system_id ID of this system
@@ -191,6 +248,20 @@ static inline uint16_t mavlink_msg_sys_tm_encode_chan(uint8_t system_id, uint8_t
     return mavlink_msg_sys_tm_pack_chan(system_id, component_id, chan, msg, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->sensors, sys_tm->actuators, sys_tm->pin_handler, sys_tm->can_handler, sys_tm->scheduler);
 }
 
+/**
+ * @brief Encode a sys_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param sys_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sys_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
+{
+    return mavlink_msg_sys_tm_pack_status(system_id, component_id, _status, msg,  sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->sensors, sys_tm->actuators, sys_tm->pin_handler, sys_tm->can_handler, sys_tm->scheduler);
+}
+
 /**
  * @brief Send a sys_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_system_tm_request_tc.h b/mavlink_lib/lyra/mavlink_msg_system_tm_request_tc.h
index de5a083eed2404c27df5ad34524fcac401fe3b6f..13ce665d295328de690bce9eba90289094544a7e 100644
--- a/mavlink_lib/lyra/mavlink_msg_system_tm_request_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_system_tm_request_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_system_tm_request_tc_pack(uint8_t system_id,
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
 }
 
+/**
+ * @brief Pack a system_tm_request_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param tm_id  A member of the SystemTMList enum
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_system_tm_request_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t tm_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN];
+    _mav_put_uint8_t(buf, 0, tm_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
+#else
+    mavlink_system_tm_request_tc_t packet;
+    packet.tm_id = tm_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a system_tm_request_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_system_tm_request_tc_encode_chan(uint8_t syst
     return mavlink_msg_system_tm_request_tc_pack_chan(system_id, component_id, chan, msg, system_tm_request_tc->tm_id);
 }
 
+/**
+ * @brief Encode a system_tm_request_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param system_tm_request_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_system_tm_request_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_system_tm_request_tc_t* system_tm_request_tc)
+{
+    return mavlink_msg_system_tm_request_tc_pack_status(system_id, component_id, _status, msg,  system_tm_request_tc->tm_id);
+}
+
 /**
  * @brief Send a system_tm_request_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_task_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_task_stats_tm.h
index b30386259c138ea1f350a58f449e55f626c58bb6..69a85810ef9ddb3c0d92cb5108613ccbbc26d1bf 100644
--- a/mavlink_lib/lyra/mavlink_msg_task_stats_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_task_stats_tm.h
@@ -123,6 +123,69 @@ static inline uint16_t mavlink_msg_task_stats_tm_pack(uint8_t system_id, uint8_t
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
 }
 
+/**
+ * @brief Pack a task_stats_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged 
+ * @param task_id  Task ID
+ * @param task_period [ns] Period of the task
+ * @param task_missed_events  Number of missed events
+ * @param task_failed_events  Number of missed events
+ * @param task_activation_mean  Task activation mean period
+ * @param task_activation_stddev  Task activation mean standard deviation
+ * @param task_period_mean  Task period mean period
+ * @param task_period_stddev  Task period mean standard deviation
+ * @param task_workload_mean  Task workload mean period
+ * @param task_workload_stddev  Task workload mean standard deviation
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_task_stats_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, uint16_t task_id, uint16_t task_period, uint32_t task_missed_events, uint32_t task_failed_events, float task_activation_mean, float task_activation_stddev, float task_period_mean, float task_period_stddev, float task_workload_mean, float task_workload_stddev)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 8, task_missed_events);
+    _mav_put_uint32_t(buf, 12, task_failed_events);
+    _mav_put_float(buf, 16, task_activation_mean);
+    _mav_put_float(buf, 20, task_activation_stddev);
+    _mav_put_float(buf, 24, task_period_mean);
+    _mav_put_float(buf, 28, task_period_stddev);
+    _mav_put_float(buf, 32, task_workload_mean);
+    _mav_put_float(buf, 36, task_workload_stddev);
+    _mav_put_uint16_t(buf, 40, task_id);
+    _mav_put_uint16_t(buf, 42, task_period);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
+#else
+    mavlink_task_stats_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.task_missed_events = task_missed_events;
+    packet.task_failed_events = task_failed_events;
+    packet.task_activation_mean = task_activation_mean;
+    packet.task_activation_stddev = task_activation_stddev;
+    packet.task_period_mean = task_period_mean;
+    packet.task_period_stddev = task_period_stddev;
+    packet.task_workload_mean = task_workload_mean;
+    packet.task_workload_stddev = task_workload_stddev;
+    packet.task_id = task_id;
+    packet.task_period = task_period;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_TASK_STATS_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a task_stats_tm message on a channel
  * @param system_id ID of this system
@@ -209,6 +272,20 @@ static inline uint16_t mavlink_msg_task_stats_tm_encode_chan(uint8_t system_id,
     return mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, chan, msg, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_missed_events, task_stats_tm->task_failed_events, task_stats_tm->task_activation_mean, task_stats_tm->task_activation_stddev, task_stats_tm->task_period_mean, task_stats_tm->task_period_stddev, task_stats_tm->task_workload_mean, task_stats_tm->task_workload_stddev);
 }
 
+/**
+ * @brief Encode a task_stats_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param task_stats_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_task_stats_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_task_stats_tm_t* task_stats_tm)
+{
+    return mavlink_msg_task_stats_tm_pack_status(system_id, component_id, _status, msg,  task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_missed_events, task_stats_tm->task_failed_events, task_stats_tm->task_activation_mean, task_stats_tm->task_activation_stddev, task_stats_tm->task_period_mean, task_stats_tm->task_period_stddev, task_stats_tm->task_workload_mean, task_stats_tm->task_workload_stddev);
+}
+
 /**
  * @brief Send a task_stats_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_temp_tm.h b/mavlink_lib/lyra/mavlink_msg_temp_tm.h
index 2ca27e7f111884943f627673009bb0df4f7cba89..c2ff251d49041056b9c6d270f5546d0ce90f21b6 100644
--- a/mavlink_lib/lyra/mavlink_msg_temp_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_temp_tm.h
@@ -73,6 +73,43 @@ static inline uint16_t mavlink_msg_temp_tm_pack(uint8_t system_id, uint8_t compo
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
 }
 
+/**
+ * @brief Pack a temp_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param sensor_name  Sensor name
+ * @param temperature [deg] Temperature
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_temp_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, const char *sensor_name, float temperature)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_TEMP_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, temperature);
+    _mav_put_char_array(buf, 12, sensor_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEMP_TM_LEN);
+#else
+    mavlink_temp_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.temperature = temperature;
+    mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEMP_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_TEMP_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a temp_tm message on a channel
  * @param system_id ID of this system
@@ -133,6 +170,20 @@ static inline uint16_t mavlink_msg_temp_tm_encode_chan(uint8_t system_id, uint8_
     return mavlink_msg_temp_tm_pack_chan(system_id, component_id, chan, msg, temp_tm->timestamp, temp_tm->sensor_name, temp_tm->temperature);
 }
 
+/**
+ * @brief Encode a temp_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param temp_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_temp_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_temp_tm_t* temp_tm)
+{
+    return mavlink_msg_temp_tm_pack_status(system_id, component_id, _status, msg,  temp_tm->timestamp, temp_tm->sensor_name, temp_tm->temperature);
+}
+
 /**
  * @brief Send a temp_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_voltage_tm.h b/mavlink_lib/lyra/mavlink_msg_voltage_tm.h
index ab5547cfbf330fadca17736e9ba1787a539be5cc..580d2e7b0a62dca892f171f050eb85aedfe918b2 100644
--- a/mavlink_lib/lyra/mavlink_msg_voltage_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_voltage_tm.h
@@ -73,6 +73,43 @@ static inline uint16_t mavlink_msg_voltage_tm_pack(uint8_t system_id, uint8_t co
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
 }
 
+/**
+ * @brief Pack a voltage_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param sensor_name  Sensor name
+ * @param voltage [V] Voltage
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_voltage_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint64_t timestamp, const char *sensor_name, float voltage)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VOLTAGE_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, voltage);
+    _mav_put_char_array(buf, 12, sensor_name, 20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
+#else
+    mavlink_voltage_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.voltage = voltage;
+    mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VOLTAGE_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a voltage_tm message on a channel
  * @param system_id ID of this system
@@ -133,6 +170,20 @@ static inline uint16_t mavlink_msg_voltage_tm_encode_chan(uint8_t system_id, uin
     return mavlink_msg_voltage_tm_pack_chan(system_id, component_id, chan, msg, voltage_tm->timestamp, voltage_tm->sensor_name, voltage_tm->voltage);
 }
 
+/**
+ * @brief Encode a voltage_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param voltage_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_voltage_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_voltage_tm_t* voltage_tm)
+{
+    return mavlink_msg_voltage_tm_pack_status(system_id, component_id, _status, msg,  voltage_tm->timestamp, voltage_tm->sensor_name, voltage_tm->voltage);
+}
+
 /**
  * @brief Send a voltage_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_wack_tm.h b/mavlink_lib/lyra/mavlink_msg_wack_tm.h
index 00837464a535d75aeddf21cedf794f6d0bceb057..752b316c6569bca77f9a0d143c8f5ff3e2d20a1a 100644
--- a/mavlink_lib/lyra/mavlink_msg_wack_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_wack_tm.h
@@ -75,6 +75,45 @@ static inline uint16_t mavlink_msg_wack_tm_pack(uint8_t system_id, uint8_t compo
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WACK_TM_MIN_LEN, MAVLINK_MSG_ID_WACK_TM_LEN, MAVLINK_MSG_ID_WACK_TM_CRC);
 }
 
+/**
+ * @brief Pack a wack_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param recv_msgid  Message id of the received message
+ * @param seq_ack  Sequence number of the received message
+ * @param err_id  Error core that generated the WACK
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_wack_tm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t recv_msgid, uint8_t seq_ack, uint16_t err_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_WACK_TM_LEN];
+    _mav_put_uint16_t(buf, 0, err_id);
+    _mav_put_uint8_t(buf, 2, recv_msgid);
+    _mav_put_uint8_t(buf, 3, seq_ack);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WACK_TM_LEN);
+#else
+    mavlink_wack_tm_t packet;
+    packet.err_id = err_id;
+    packet.recv_msgid = recv_msgid;
+    packet.seq_ack = seq_ack;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WACK_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_WACK_TM;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_WACK_TM_MIN_LEN, MAVLINK_MSG_ID_WACK_TM_LEN, MAVLINK_MSG_ID_WACK_TM_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_WACK_TM_MIN_LEN, MAVLINK_MSG_ID_WACK_TM_LEN);
+#endif
+}
+
 /**
  * @brief Pack a wack_tm message on a channel
  * @param system_id ID of this system
@@ -137,6 +176,20 @@ static inline uint16_t mavlink_msg_wack_tm_encode_chan(uint8_t system_id, uint8_
     return mavlink_msg_wack_tm_pack_chan(system_id, component_id, chan, msg, wack_tm->recv_msgid, wack_tm->seq_ack, wack_tm->err_id);
 }
 
+/**
+ * @brief Encode a wack_tm struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param wack_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_wack_tm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_wack_tm_t* wack_tm)
+{
+    return mavlink_msg_wack_tm_pack_status(system_id, component_id, _status, msg,  wack_tm->recv_msgid, wack_tm->seq_ack, wack_tm->err_id);
+}
+
 /**
  * @brief Send a wack_tm message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/mavlink_msg_wiggle_servo_tc.h b/mavlink_lib/lyra/mavlink_msg_wiggle_servo_tc.h
index 8b127cb2933322c63c571b82f866e87968fa5873..10febbf015fd87078ec354185bb4a3c4e4cd99f6 100644
--- a/mavlink_lib/lyra/mavlink_msg_wiggle_servo_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_wiggle_servo_tc.h
@@ -63,6 +63,39 @@ static inline uint16_t mavlink_msg_wiggle_servo_tc_pack(uint8_t system_id, uint8
     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
 }
 
+/**
+ * @brief Pack a wiggle_servo_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param servo_id  A member of the ServosList enum
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_wiggle_servo_tc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint8_t servo_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN];
+    _mav_put_uint8_t(buf, 0, servo_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
+#else
+    mavlink_wiggle_servo_tc_t packet;
+    packet.servo_id = servo_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_WIGGLE_SERVO_TC;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
+#endif
+}
+
 /**
  * @brief Pack a wiggle_servo_tc message on a channel
  * @param system_id ID of this system
@@ -119,6 +152,20 @@ static inline uint16_t mavlink_msg_wiggle_servo_tc_encode_chan(uint8_t system_id
     return mavlink_msg_wiggle_servo_tc_pack_chan(system_id, component_id, chan, msg, wiggle_servo_tc->servo_id);
 }
 
+/**
+ * @brief Encode a wiggle_servo_tc struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param wiggle_servo_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_wiggle_servo_tc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
+{
+    return mavlink_msg_wiggle_servo_tc_pack_status(system_id, component_id, _status, msg,  wiggle_servo_tc->servo_id);
+}
+
 /**
  * @brief Send a wiggle_servo_tc message
  * @param chan MAVLink channel to send the message
diff --git a/mavlink_lib/lyra/testsuite.h b/mavlink_lib/lyra/testsuite.h
index dffedd002cada3850a9381b7d1e54197a3603f54..73f55c540989860e2c15e0b8d672f5dc11f67e0d 100644
--- a/mavlink_lib/lyra/testsuite.h
+++ b/mavlink_lib/lyra/testsuite.h
@@ -2663,7 +2663,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,37,104,171,238,49
+        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
     };
     mavlink_arp_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -2695,6 +2695,8 @@ static void mavlink_test_arp_tm(uint8_t system_id, uint8_t component_id, mavlink
         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;
@@ -2714,12 +2716,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.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 );
+    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_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.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 );
+    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_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2732,7 +2734,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.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 );
+    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_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2754,12 +2756,13 @@ static void mavlink_test_set_antenna_coordinates_arp_tc(uint8_t system_id, uint8
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_set_antenna_coordinates_arp_tc_t packet_in = {
-        17.0,45.0
+        17.0,45.0,73.0
     };
     mavlink_set_antenna_coordinates_arp_tc_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.latitude = packet_in.latitude;
         packet1.longitude = packet_in.longitude;
+        packet1.height = packet_in.height;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -2774,12 +2777,12 @@ static void mavlink_test_set_antenna_coordinates_arp_tc(uint8_t system_id, uint8
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_antenna_coordinates_arp_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
+    mavlink_msg_set_antenna_coordinates_arp_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.height );
     mavlink_msg_set_antenna_coordinates_arp_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
+    mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.height );
     mavlink_msg_set_antenna_coordinates_arp_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2792,7 +2795,7 @@ static void mavlink_test_set_antenna_coordinates_arp_tc(uint8_t system_id, uint8
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_antenna_coordinates_arp_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
+    mavlink_msg_set_antenna_coordinates_arp_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude , packet1.height );
     mavlink_msg_set_antenna_coordinates_arp_tc_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2814,12 +2817,13 @@ static void mavlink_test_set_rocket_coordinates_arp_tc(uint8_t system_id, uint8_
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_set_rocket_coordinates_arp_tc_t packet_in = {
-        17.0,45.0
+        17.0,45.0,73.0
     };
     mavlink_set_rocket_coordinates_arp_tc_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.latitude = packet_in.latitude;
         packet1.longitude = packet_in.longitude;
+        packet1.height = packet_in.height;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -2834,12 +2838,12 @@ static void mavlink_test_set_rocket_coordinates_arp_tc(uint8_t system_id, uint8_
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_rocket_coordinates_arp_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
+    mavlink_msg_set_rocket_coordinates_arp_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.height );
     mavlink_msg_set_rocket_coordinates_arp_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
+    mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.height );
     mavlink_msg_set_rocket_coordinates_arp_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2852,7 +2856,7 @@ static void mavlink_test_set_rocket_coordinates_arp_tc(uint8_t system_id, uint8_
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_rocket_coordinates_arp_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
+    mavlink_msg_set_rocket_coordinates_arp_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude , packet1.height );
     mavlink_msg_set_rocket_coordinates_arp_tc_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2862,6 +2866,65 @@ static void mavlink_test_set_rocket_coordinates_arp_tc(uint8_t system_id, uint8_
 #endif
 }
 
+static void mavlink_test_arp_command_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ARP_COMMAND_TC >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_arp_command_tc_t packet_in = {
+        5
+    };
+    mavlink_arp_command_tc_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.command_id = packet_in.command_id;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_arp_command_tc_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_arp_command_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_arp_command_tc_pack(system_id, component_id, &msg , packet1.command_id );
+    mavlink_msg_arp_command_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_arp_command_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command_id );
+    mavlink_msg_arp_command_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_arp_command_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_arp_command_tc_send(MAVLINK_COMM_1 , packet1.command_id );
+    mavlink_msg_arp_command_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("ARP_COMMAND_TC") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ARP_COMMAND_TC) != NULL);
+#endif
+}
+
 static void mavlink_test_sys_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -3874,7 +3937,7 @@ static void mavlink_test_motor_tm(uint8_t system_id, uint8_t component_id, mavli
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_motor_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,963498920,18899,235,46,113
+        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,963498920,18899,235,46,113,180
     };
     mavlink_motor_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -3886,6 +3949,7 @@ static void mavlink_test_motor_tm(uint8_t system_id, uint8_t component_id, mavli
         packet1.battery_voltage = packet_in.battery_voltage;
         packet1.writes_failed = packet_in.writes_failed;
         packet1.log_number = packet_in.log_number;
+        packet1.floating_level = packet_in.floating_level;
         packet1.main_valve_state = packet_in.main_valve_state;
         packet1.venting_valve_state = packet_in.venting_valve_state;
         packet1.hil_state = packet_in.hil_state;
@@ -3903,12 +3967,12 @@ static void mavlink_test_motor_tm(uint8_t system_id, uint8_t component_id, mavli
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_motor_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.log_number , packet1.writes_failed , packet1.hil_state );
+    mavlink_msg_motor_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.log_number , packet1.writes_failed , packet1.hil_state );
     mavlink_msg_motor_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_motor_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.log_number , packet1.writes_failed , packet1.hil_state );
+    mavlink_msg_motor_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.log_number , packet1.writes_failed , packet1.hil_state );
     mavlink_msg_motor_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3921,7 +3985,7 @@ static void mavlink_test_motor_tm(uint8_t system_id, uint8_t component_id, mavli
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_motor_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.log_number , packet1.writes_failed , packet1.hil_state );
+    mavlink_msg_motor_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.log_number , packet1.writes_failed , packet1.hil_state );
     mavlink_msg_motor_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3979,6 +4043,7 @@ static void mavlink_test_lyra(uint8_t system_id, uint8_t component_id, mavlink_m
     mavlink_test_arp_tm(system_id, component_id, last_msg);
     mavlink_test_set_antenna_coordinates_arp_tc(system_id, component_id, last_msg);
     mavlink_test_set_rocket_coordinates_arp_tc(system_id, component_id, last_msg);
+    mavlink_test_arp_command_tc(system_id, component_id, last_msg);
     mavlink_test_sys_tm(system_id, component_id, last_msg);
     mavlink_test_logger_tm(system_id, component_id, last_msg);
     mavlink_test_mavlink_stats_tm(system_id, component_id, last_msg);
diff --git a/mavlink_lib/lyra/version.h b/mavlink_lib/lyra/version.h
index 0695e77cc3818b6b875376df7b9c5e9ac08cd16e..4886d5b02c53ea93f7621c02784882d8960b4e4b 100644
--- a/mavlink_lib/lyra/version.h
+++ b/mavlink_lib/lyra/version.h
@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Thu Jun 27 2024"
+#define MAVLINK_BUILD_DATE "Tue Jul 02 2024"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 170
  
diff --git a/mavlink_lib/mavlink_helpers.h b/mavlink_lib/mavlink_helpers.h
index 22e5d406c794010a8809ed2d9fb0765d9a7e06e5..73a713304926437e07dcb70ca4cf91583bf027cc 100644
--- a/mavlink_lib/mavlink_helpers.h
+++ b/mavlink_lib/mavlink_helpers.h
@@ -52,6 +52,46 @@ MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan)
 	status->parse_state = MAVLINK_PARSE_STATE_IDLE;
 }
 
+/**
+ * @brief Finalize a MAVLink message with channel assignment
+ *
+ * This function calculates the checksum and sets length and aircraft id correctly.
+ * It assumes that the message id and the payload are already correctly set. This function
+ * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack
+ * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.
+ *
+ * @param msg Message to finalize
+ * @param system_id Id of the sending (this) system, 1-127
+ * @param length Message length
+ */
+#if MAVLINK_CRC_EXTRA
+MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+                                                        mavlink_status_t* status, uint8_t min_length, uint8_t length, uint8_t crc_extra)
+#else
+MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+                                                        mavlink_status_t* status, uint8_t length)
+#endif
+{
+	// This is only used for the v2 protocol and we silence it here
+	(void)min_length;
+	// This code part is the same for all messages;
+	msg->magic = MAVLINK_STX;
+	msg->len = length;
+	msg->sysid = system_id;
+	msg->compid = component_id;
+    msg->seq = status->current_tx_seq;
+    status->current_tx_seq = status->current_tx_seq+1;
+	msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN);
+	crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len);
+#if MAVLINK_CRC_EXTRA
+	crc_accumulate(crc_extra, &msg->checksum);
+#endif
+	mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF);
+	mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8);
+
+	return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+}
+
 /**
  * @brief Finalize a MAVLink message with channel assignment
  *
@@ -72,7 +112,7 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, ui
 						      uint8_t chan, uint8_t length)
 #endif
 {
-	// This is only used for the v2 protocol and we silence it here
+    // This is only used for the v2 protocol and we silence it here
 	(void)min_length;
 	// This code part is the same for all messages;
 	msg->magic = MAVLINK_STX;
@@ -248,8 +288,6 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
 #endif
 #endif
 
-	int bufferIndex = 0;
-
 	status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
 
 	switch (status->parse_state)
@@ -364,7 +402,6 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
 		break;
 	}
 
-	bufferIndex++;
 	// If a message has been successfully decoded, check index
 	if (status->msg_received == MAVLINK_FRAMING_OK)
 	{
diff --git a/mavlink_lib/protocol.h b/mavlink_lib/protocol.h
index 34749d9ba7106edf5de0486145fdde0e31aeec55..f48d947f1c94ad16d8a358b5234cd12b0c1c4775 100644
--- a/mavlink_lib/protocol.h
+++ b/mavlink_lib/protocol.h
@@ -45,6 +45,8 @@
     #endif
     MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan);
     #if MAVLINK_CRC_EXTRA
+    MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+                                                            mavlink_status_t* status, uint8_t min_length, uint8_t length, uint8_t crc_extra);
     MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
                                                           uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra);
     MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
@@ -54,6 +56,8 @@
                                                         uint8_t min_length, uint8_t length, uint8_t crc_extra);
     #endif
     #else
+    MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+                                                            mavlink_status_t* status, uint8_t min_length, uint8_t length);
     MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
                                                           uint8_t chan, uint8_t length);
     MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,