''' MAVLink protocol implementation (auto-generated by mavgen.py) 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' PROTOCOL_MARKER_V1 = 0xFE PROTOCOL_MARKER_V2 = 0xFD HEADER_LEN_V1 = 6 HEADER_LEN_V2 = 10 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 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 # 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) # some base types from mavlink_types.h 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_UINT32_T = 5 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' 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): self.mlen = mlen self.seq = seq self.srcSystem = srcSystem self.srcComponent = srcComponent self.msgId = msgId 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) 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) if isinstance(raw_attr, bytes): raw_attr = to_string(raw_attr).rstrip("\00") return raw_attr def get_msgbuf(self): if isinstance(self._msgbuf, bytearray): return self._msgbuf return bytearray(self._msgbuf) def get_header(self): return self._header def get_payload(self): return self._payload def get_crc(self): return self._crc def get_fieldnames(self): return self._fieldnames def get_type(self): return self._type def get_msgId(self): return self._header.msgId def get_srcSystem(self): return self._header.srcSystem def get_srcComponent(self): return self._header.srcComponent def get_seq(self): return self._header.seq def get_signed(self): return self._signed def get_link_id(self): return self._link_id def __str__(self): ret = '%s {' % self._type for a in self._fieldnames: v = self.format_attr(a) ret += '%s : %s, ' % (a, v) ret = ret[0:-2] + '}' return ret def __ne__(self, other): return not self.__eq__(other) def __eq__(self, other): if other is None: 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_seq() != other.get_seq(): return False if self.get_srcSystem() != other.get_srcSystem(): return False if self.get_srcComponent() != other.get_srcComponent(): return False for a in self._fieldnames: if self.format_attr(a) != other.format_attr(a): return False return True def to_dict(self): d = dict({}) d['mavpackettype'] = self._type for a in self._fieldnames: d[a] = self.format_attr(a) return d def to_json(self): 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] 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): plen = len(payload) if WIRE_PROTOCOL_VERSION != '1.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'>": nullbyte = 0 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 crc = x25crc(self._msgbuf[1:]) if True: # using CRC extra crc.accumulate_str(struct.pack('B', crc_extra)) self._crc = crc.crc self._msgbuf += struct.pack('<H', self._crc) if mav.signing.sign_outgoing and not force_mavlink1: self.sign_packet(mav) return self._msgbuf def __getitem__(self, key): '''support indexing, allowing for multi-instance sensors in one message''' if self._instances is None: raise IndexError() if not key in self._instances: raise IndexError() return self._instances[key] # enums class EnumEntry(object): def __init__(self, name, description): self.name = name self.description = description self.param = {} enums = {} # 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', '''''') 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''') MAV_REFERENCE_ID = 16 # Command to fetch reference values enums['SystemTMList'][16] = EnumEntry('MAV_REFERENCE_ID', '''Command to fetch reference values''') MAV_CALIBRATION_ID = 17 # Command to fetch calibration values enums['SystemTMList'][17] = EnumEntry('MAV_CALIBRATION_ID', '''Command to fetch calibration values''') SystemTMList_ENUM_END = 18 # enums['SystemTMList'][18] = 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', '''''') # 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''') MAV_CMD_EXIT_HIL = 23 # Command to exit HIL mode at next reboot enums['MavCommandList'][23] = EnumEntry('MAV_CMD_EXIT_HIL', '''Command to exit HIL mode at next reboot''') MAV_CMD_RESET_ALGORITHM = 24 # Command to reset the set algorithm. Used for now in ARP to reset the # follow algorithm and return to armed state. enums['MavCommandList'][24] = EnumEntry('MAV_CMD_RESET_ALGORITHM', '''Command to reset the set algorithm. Used for now in ARP to reset the follow algorithm and return to armed state.''') MAV_CMD_ARP_FORCE_NO_FEEDBACK = 25 # Command to force ARP system to entern the no feedback from VN300 state enums['MavCommandList'][25] = EnumEntry('MAV_CMD_ARP_FORCE_NO_FEEDBACK', '''Command to force ARP system to entern the no feedback from VN300 state''') MAV_CMD_ARP_FOLLOW = 26 # Command to enter in the ARP's follow state and procedure to follow the # rocket enums['MavCommandList'][26] = EnumEntry('MAV_CMD_ARP_FOLLOW', '''Command to enter in the ARP's follow state and procedure to follow the rocket''') MavCommandList_ENUM_END = 27 # enums['MavCommandList'][27] = EnumEntry('MavCommandList_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', '''''') # 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', '''''') # PinsList enums['PinsList'] = {} RAMP_PIN = 1 # enums['PinsList'][1] = EnumEntry('RAMP_PIN', '''''') NOSECONE_PIN = 2 # enums['PinsList'][2] = EnumEntry('NOSECONE_PIN', '''''') PinsList_ENUM_END = 3 # enums['PinsList'][3] = EnumEntry('PinsList_ENUM_END', '''''') # message IDs MAVLINK_MSG_ID_BAD_DATA = -1 MAVLINK_MSG_ID_UNKNOWN = -2 MAVLINK_MSG_ID_PING_TC = 1 MAVLINK_MSG_ID_COMMAND_TC = 2 MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC = 3 MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC = 4 MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC = 5 MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC = 6 MAVLINK_MSG_ID_RESET_SERVO_TC = 7 MAVLINK_MSG_ID_WIGGLE_SERVO_TC = 8 MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC = 9 MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC = 10 MAVLINK_MSG_ID_SET_ORIENTATION_TC = 11 MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC = 12 MAVLINK_MSG_ID_SET_COORDINATES_TC = 13 MAVLINK_MSG_ID_RAW_EVENT_TC = 14 MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC = 15 MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC = 16 MAVLINK_MSG_ID_SET_ALGORITHM_TC = 17 MAVLINK_MSG_ID_SET_CALIBRATION_PRESSURE_TC = 18 MAVLINK_MSG_ID_SET_INITIAL_MEA_MASS_TC = 19 MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC = 30 MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC = 31 MAVLINK_MSG_ID_CONRIG_STATE_TC = 32 MAVLINK_MSG_ID_SET_IGNITION_TIME_TC = 33 MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC = 34 MAVLINK_MSG_ID_SET_COOLING_TIME_TC = 35 MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC = 60 MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC = 61 MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC = 62 MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC = 63 MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC = 64 MAVLINK_MSG_ID_ARP_COMMAND_TC = 65 MAVLINK_MSG_ID_ACK_TM = 100 MAVLINK_MSG_ID_NACK_TM = 101 MAVLINK_MSG_ID_WACK_TM = 102 MAVLINK_MSG_ID_GPS_TM = 103 MAVLINK_MSG_ID_IMU_TM = 104 MAVLINK_MSG_ID_PRESSURE_TM = 105 MAVLINK_MSG_ID_ADC_TM = 106 MAVLINK_MSG_ID_VOLTAGE_TM = 107 MAVLINK_MSG_ID_CURRENT_TM = 108 MAVLINK_MSG_ID_TEMP_TM = 109 MAVLINK_MSG_ID_LOAD_TM = 110 MAVLINK_MSG_ID_ATTITUDE_TM = 111 MAVLINK_MSG_ID_SENSOR_STATE_TM = 112 MAVLINK_MSG_ID_SERVO_TM = 113 MAVLINK_MSG_ID_PIN_TM = 114 MAVLINK_MSG_ID_REFERENCE_TM = 115 MAVLINK_MSG_ID_REGISTRY_FLOAT_TM = 116 MAVLINK_MSG_ID_REGISTRY_INT_TM = 117 MAVLINK_MSG_ID_REGISTRY_COORD_TM = 118 MAVLINK_MSG_ID_ARP_TM = 150 MAVLINK_MSG_ID_SYS_TM = 200 MAVLINK_MSG_ID_LOGGER_TM = 201 MAVLINK_MSG_ID_MAVLINK_STATS_TM = 202 MAVLINK_MSG_ID_CAN_STATS_TM = 203 MAVLINK_MSG_ID_TASK_STATS_TM = 204 MAVLINK_MSG_ID_ADA_TM = 205 MAVLINK_MSG_ID_NAS_TM = 206 MAVLINK_MSG_ID_MEA_TM = 207 MAVLINK_MSG_ID_ROCKET_FLIGHT_TM = 208 MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM = 209 MAVLINK_MSG_ID_ROCKET_STATS_TM = 210 MAVLINK_MSG_ID_PAYLOAD_STATS_TM = 211 MAVLINK_MSG_ID_GSE_TM = 212 MAVLINK_MSG_ID_MOTOR_TM = 213 MAVLINK_MSG_ID_CALIBRATION_TM = 214 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) class MAVLink_set_calibration_pressure_tc_message(MAVLink_message): ''' Set the pressure used for analog pressure calibration ''' id = MAVLINK_MSG_ID_SET_CALIBRATION_PRESSURE_TC name = 'SET_CALIBRATION_PRESSURE_TC' fieldnames = ['pressure'] ordered_fieldnames = ['pressure'] fieldtypes = ['float'] fielddisplays_by_name = {} fieldenums_by_name = {} fieldunits_by_name = {"pressure": "Pa"} format = '<f' native_format = bytearray('<f', 'ascii') orders = [0] lengths = [1] array_lengths = [0] crc_extra = 199 unpacker = struct.Struct('<f') instance_field = None instance_offset = -1 def __init__(self, pressure): MAVLink_message.__init__(self, MAVLink_set_calibration_pressure_tc_message.id, MAVLink_set_calibration_pressure_tc_message.name) self._fieldnames = MAVLink_set_calibration_pressure_tc_message.fieldnames self._instance_field = MAVLink_set_calibration_pressure_tc_message.instance_field self._instance_offset = MAVLink_set_calibration_pressure_tc_message.instance_offset self.pressure = pressure def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 199, struct.pack('<f', self.pressure), force_mavlink1=force_mavlink1) class MAVLink_set_initial_mea_mass_tc_message(MAVLink_message): ''' Set the initial MEA mass ''' id = MAVLINK_MSG_ID_SET_INITIAL_MEA_MASS_TC name = 'SET_INITIAL_MEA_MASS_TC' fieldnames = ['mass'] ordered_fieldnames = ['mass'] fieldtypes = ['float'] fielddisplays_by_name = {} fieldenums_by_name = {} fieldunits_by_name = {"mass": "kg"} format = '<f' native_format = bytearray('<f', 'ascii') orders = [0] lengths = [1] array_lengths = [0] crc_extra = 221 unpacker = struct.Struct('<f') instance_field = None instance_offset = -1 def __init__(self, mass): MAVLink_message.__init__(self, MAVLink_set_initial_mea_mass_tc_message.id, MAVLink_set_initial_mea_mass_tc_message.name) self._fieldnames = MAVLink_set_initial_mea_mass_tc_message.fieldnames self._instance_field = MAVLink_set_initial_mea_mass_tc_message.instance_field self._instance_offset = MAVLink_set_initial_mea_mass_tc_message.instance_offset self.mass = mass def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 221, struct.pack('<f', self.mass), force_mavlink1=force_mavlink1) 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) 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) 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) 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) 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) 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) 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) 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) class MAVLink_set_stepper_multiplier_tc_message(MAVLink_message): ''' Set the multiplier of the stepper ''' id = MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC name = 'SET_STEPPER_MULTIPLIER_TC' fieldnames = ['stepper_id', 'multiplier'] ordered_fieldnames = ['multiplier', '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 = 173 unpacker = struct.Struct('<fB') instance_field = None instance_offset = -1 def __init__(self, stepper_id, multiplier): MAVLink_message.__init__(self, MAVLink_set_stepper_multiplier_tc_message.id, MAVLink_set_stepper_multiplier_tc_message.name) self._fieldnames = MAVLink_set_stepper_multiplier_tc_message.fieldnames self._instance_field = MAVLink_set_stepper_multiplier_tc_message.instance_field self._instance_offset = MAVLink_set_stepper_multiplier_tc_message.instance_offset self.stepper_id = stepper_id self.multiplier = multiplier def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 173, struct.pack('<fB', self.multiplier, self.stepper_id), force_mavlink1=force_mavlink1) 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', 'height'] ordered_fieldnames = ['latitude', 'longitude', 'height'] fieldtypes = ['float', 'float', 'float'] fielddisplays_by_name = {} fieldenums_by_name = {} fieldunits_by_name = {"latitude": "deg", "longitude": "deg", "height": "m"} format = '<fff' native_format = bytearray('<fff', 'ascii') 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, longitude, height): 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 self.height = height def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 183, struct.pack('<fff', self.latitude, self.longitude, self.height), force_mavlink1=force_mavlink1) 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', 'height'] ordered_fieldnames = ['latitude', 'longitude', 'height'] fieldtypes = ['float', 'float', 'float'] fielddisplays_by_name = {} fieldenums_by_name = {} fieldunits_by_name = {"latitude": "deg", "longitude": "deg", "height": "m"} format = '<fff' native_format = bytearray('<fff', 'ascii') 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, longitude, height): 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 self.height = height def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 220, struct.pack('<fff', self.latitude, self.longitude, self.height), force_mavlink1=force_mavlink1) 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 name = 'ARP_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 = 181 unpacker = struct.Struct('<B') instance_field = None instance_offset = -1 def __init__(self, command_id): MAVLink_message.__init__(self, MAVLink_arp_command_tc_message.id, MAVLink_arp_command_tc_message.name) 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, force_mavlink1=False): return MAVLink_message.pack(self, mav, 181, struct.pack('<B', self.command_id), force_mavlink1=force_mavlink1) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) 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) class MAVLink_reference_tm_message(MAVLink_message): ''' ''' id = MAVLINK_MSG_ID_REFERENCE_TM name = 'REFERENCE_TM' fieldnames = ['timestamp', 'ref_altitude', 'ref_pressure', 'ref_temperature', 'ref_latitude', 'ref_longitude', 'msl_pressure', 'msl_temperature'] ordered_fieldnames = ['timestamp', 'ref_altitude', 'ref_pressure', 'ref_temperature', 'ref_latitude', 'ref_longitude', 'msl_pressure', 'msl_temperature'] fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float'] fielddisplays_by_name = {} fieldenums_by_name = {} fieldunits_by_name = {"timestamp": "us", "ref_altitude": "m", "ref_pressure": "Pa", "ref_temperature": "degC", "ref_latitude": "deg", "ref_longitude": "deg", "msl_pressure": "Pa", "msl_temperature": "degC"} format = '<Qfffffff' native_format = bytearray('<Qfffffff', 'ascii') orders = [0, 1, 2, 3, 4, 5, 6, 7] lengths = [1, 1, 1, 1, 1, 1, 1, 1] array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] crc_extra = 103 unpacker = struct.Struct('<Qfffffff') instance_field = None instance_offset = -1 def __init__(self, timestamp, ref_altitude, ref_pressure, ref_temperature, ref_latitude, ref_longitude, msl_pressure, msl_temperature): MAVLink_message.__init__(self, MAVLink_reference_tm_message.id, MAVLink_reference_tm_message.name) self._fieldnames = MAVLink_reference_tm_message.fieldnames self._instance_field = MAVLink_reference_tm_message.instance_field self._instance_offset = MAVLink_reference_tm_message.instance_offset self.timestamp = timestamp self.ref_altitude = ref_altitude self.ref_pressure = ref_pressure self.ref_temperature = ref_temperature self.ref_latitude = ref_latitude self.ref_longitude = ref_longitude self.msl_pressure = msl_pressure self.msl_temperature = msl_temperature def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 103, struct.pack('<Qfffffff', self.timestamp, self.ref_altitude, self.ref_pressure, self.ref_temperature, self.ref_latitude, self.ref_longitude, self.msl_pressure, self.msl_temperature), force_mavlink1=force_mavlink1) 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) 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) 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) class MAVLink_arp_tm_message(MAVLink_message): ''' ''' id = MAVLINK_MSG_ID_ARP_TM name = 'ARP_TM' fieldnames = ['timestamp', 'state', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'gps_fix', 'main_radio_present', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'main_rx_rssi', 'payload_radio_present', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'payload_rx_rssi', 'ethernet_present', 'ethernet_status', 'battery_voltage', 'log_number'] ordered_fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'main_rx_rssi', 'payload_rx_rssi', 'battery_voltage', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'log_number', 'state', 'gps_fix', 'main_radio_present', 'payload_radio_present', 'ethernet_present', 'ethernet_status'] fieldtypes = ['uint64_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'uint8_t', 'uint8_t', 'float', 'int16_t'] fielddisplays_by_name = {} fieldenums_by_name = {} fieldunits_by_name = {"timestamp": "us", "yaw": "deg", "pitch": "deg", "roll": "deg", "target_yaw": "deg", "target_pitch": "deg", "stepperX_pos": "deg", "stepperX_delta": "deg", "stepperX_speed": "rps", "stepperY_pos": "deg", "stepperY_delta": "deg", "stepperY_speed": "rps", "gps_latitude": "deg", "gps_longitude": "deg", "gps_height": "m", "main_tx_bitrate": "b/s", "main_rx_bitrate": "b/s", "main_rx_rssi": "dBm", "payload_tx_bitrate": "b/s", "payload_rx_bitrate": "b/s", "payload_rx_rssi": "dBm", "battery_voltage": "V"} format = '<QfffffffffffffffffHHHHHHHHHHhBBBBBB' native_format = bytearray('<QfffffffffffffffffHHHHHHHHHHhBBBBBB', 'ascii') orders = [0, 29, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 30, 31, 18, 19, 20, 21, 22, 15, 32, 23, 24, 25, 26, 27, 16, 33, 34, 17, 28] lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] crc_extra = 239 unpacker = struct.Struct('<QfffffffffffffffffHHHHHHHHHHhBBBBBB') instance_field = None instance_offset = -1 def __init__(self, timestamp, state, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, ethernet_present, ethernet_status, battery_voltage, log_number): 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.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, force_mavlink1=False): return MAVLink_message.pack(self, mav, 239, struct.pack('<QfffffffffffffffffHHHHHHHHHHhBBBBBB', self.timestamp, self.yaw, self.pitch, self.roll, self.target_yaw, self.target_pitch, self.stepperX_pos, self.stepperX_delta, self.stepperX_speed, self.stepperY_pos, self.stepperY_delta, self.stepperY_speed, self.gps_latitude, self.gps_longitude, self.gps_height, self.main_rx_rssi, self.payload_rx_rssi, self.battery_voltage, self.main_packet_tx_error_count, self.main_tx_bitrate, self.main_packet_rx_success_count, self.main_packet_rx_drop_count, self.main_rx_bitrate, self.payload_packet_tx_error_count, self.payload_tx_bitrate, self.payload_packet_rx_success_count, self.payload_packet_rx_drop_count, self.payload_rx_bitrate, self.log_number, self.state, self.gps_fix, self.main_radio_present, self.payload_radio_present, self.ethernet_present, self.ethernet_status), force_mavlink1=force_mavlink1) 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) 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) 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) 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) 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) 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) 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) 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) class MAVLink_rocket_flight_tm_message(MAVLink_message): ''' High Rate Rocket Telemetry ''' id = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM name = 'ROCKET_FLIGHT_TM' fieldnames = ['timestamp', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'mea_apogee', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'vn100_qx', 'vn100_qy', 'vn100_qz', 'vn100_qw', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'fmm_state', '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'] ordered_fieldnames = ['timestamp', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'mea_apogee', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'vn100_qx', 'vn100_qy', 'vn100_qz', 'vn100_qw', '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', 'gps_fix', 'fmm_state'] fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'uint8_t', 'float', '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", "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", "mea_apogee": "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", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "battery_voltage": "V", "cam_battery_voltage": "V", "temperature": "degC"} format = '<QffffffffffffffffffffffffffffffffffffffffffBB' native_format = bytearray('<QffffffffffffffffffffffffffffffffffffffffffBB', 'ascii') orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 43, 23, 24, 25, 44, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42] lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] crc_extra = 235 unpacker = struct.Struct('<QffffffffffffffffffffffffffffffffffffffffffBB') instance_field = None instance_offset = -1 def __init__(self, timestamp, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, mea_apogee, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, vn100_qx, vn100_qy, vn100_qz, vn100_qw, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, 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): 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.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.mea_apogee = mea_apogee 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.vn100_qx = vn100_qx self.vn100_qy = vn100_qy self.vn100_qz = vn100_qz self.vn100_qw = vn100_qw self.gps_fix = gps_fix self.gps_lat = gps_lat self.gps_lon = gps_lon self.gps_alt = gps_alt self.fmm_state = fmm_state 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.battery_voltage = battery_voltage self.cam_battery_voltage = cam_battery_voltage self.temperature = temperature def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 235, struct.pack('<QffffffffffffffffffffffffffffffffffffffffffBB', 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.mea_apogee, 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.vn100_qx, self.vn100_qy, self.vn100_qz, self.vn100_qw, 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.gps_fix, self.fmm_state), force_mavlink1=force_mavlink1) class MAVLink_payload_flight_tm_message(MAVLink_message): ''' High Rate Payload Telemetry ''' id = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM name = 'PAYLOAD_FLIGHT_TM' fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'pressure_dynamic', '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', 'fmm_state', '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'] ordered_fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'pressure_dynamic', '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', 'gps_fix', 'fmm_state'] fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', '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'] fielddisplays_by_name = {} fieldenums_by_name = {} fieldunits_by_name = {"timestamp": "us", "pressure_digi": "Pa", "pressure_static": "Pa", "pressure_dynamic": "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", "wes_n": "m/s", "wes_e": "m/s", "battery_voltage": "V", "cam_battery_voltage": "V", "temperature": "degC"} format = '<QfffffffffffffffffffffffffffffffffffffBB' native_format = bytearray('<QfffffffffffffffffffffffffffffffffffffBB', 'ascii') orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 38, 15, 16, 17, 39, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37] 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] 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] crc_extra = 188 unpacker = struct.Struct('<QfffffffffffffffffffffffffffffffffffffBB') instance_field = None instance_offset = -1 def __init__(self, timestamp, pressure_digi, pressure_static, pressure_dynamic, 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, fmm_state, 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): 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.pressure_digi = pressure_digi self.pressure_static = pressure_static self.pressure_dynamic = pressure_dynamic 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.fmm_state = fmm_state 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.battery_voltage = battery_voltage self.cam_battery_voltage = cam_battery_voltage self.temperature = temperature def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 188, struct.pack('<QfffffffffffffffffffffffffffffffffffffBB', self.timestamp, self.pressure_digi, self.pressure_static, self.pressure_dynamic, 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.gps_fix, self.fmm_state), force_mavlink1=force_mavlink1) class MAVLink_rocket_stats_tm_message(MAVLink_message): ''' Low Rate Rocket Telemetry ''' id = MAVLINK_MSG_ID_ROCKET_STATS_TM name = 'ROCKET_STATS_TM' fieldnames = ['timestamp', 'liftoff_ts', 'liftoff_max_acc_ts', 'liftoff_max_acc', 'max_speed_ts', 'max_speed', 'max_speed_altitude', 'max_mach_ts', 'max_mach', 'shutdown_ts', 'shutdown_alt', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'apogee_max_acc_ts', 'apogee_max_acc', 'dpl_ts', 'dpl_alt', 'dpl_max_acc_ts', 'dpl_max_acc', 'dpl_bay_max_pressure_ts', 'dpl_bay_max_pressure', 'ref_lat', 'ref_lon', 'ref_alt', 'cpu_load', 'free_heap', 'ada_state', 'abk_state', 'nas_state', 'mea_state', 'exp_angle', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'log_number', 'log_good', 'payload_board_state', 'motor_board_state', 'payload_can_status', 'motor_can_status', 'rig_can_status', 'hil_state'] ordered_fieldnames = ['timestamp', 'liftoff_ts', 'liftoff_max_acc_ts', 'max_speed_ts', 'max_mach_ts', 'shutdown_ts', 'apogee_ts', 'apogee_max_acc_ts', 'dpl_ts', 'dpl_max_acc_ts', 'dpl_bay_max_pressure_ts', 'liftoff_max_acc', 'max_speed', 'max_speed_altitude', 'max_mach', 'shutdown_alt', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'apogee_max_acc', 'dpl_alt', 'dpl_max_acc', 'dpl_bay_max_pressure', 'ref_lat', 'ref_lon', 'ref_alt', 'cpu_load', 'free_heap', 'exp_angle', 'log_good', 'log_number', 'ada_state', 'abk_state', 'nas_state', 'mea_state', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'payload_board_state', 'motor_board_state', 'payload_can_status', 'motor_can_status', 'rig_can_status', 'hil_state'] fieldtypes = ['uint64_t', 'uint64_t', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'uint32_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'int16_t', 'int32_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t'] fielddisplays_by_name = {} fieldenums_by_name = {} fieldunits_by_name = {"timestamp": "us", "liftoff_ts": "us", "liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "max_speed_ts": "us", "max_speed": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "apogee_max_acc_ts": "us", "apogee_max_acc": "m/s2", "dpl_ts": "us", "dpl_alt": "m", "dpl_max_acc_ts": "us", "dpl_max_acc": "m/s2", "dpl_bay_max_pressure_ts": "us", "dpl_bay_max_pressure": "Pa", "ref_lat": "deg", "ref_lon": "deg", "ref_alt": "m"} format = '<QQQQQQQQQQQffffffffffffffffIfihBBBBBBBBBBBBBB' native_format = bytearray('<QQQQQQQQQQQffffffffffffffffIfihBBBBBBBBBBBBBB', 'ascii') orders = [0, 1, 2, 11, 3, 12, 13, 4, 14, 5, 15, 6, 16, 17, 18, 7, 19, 8, 20, 9, 21, 10, 22, 23, 24, 25, 26, 27, 31, 32, 33, 34, 28, 35, 36, 37, 38, 30, 29, 39, 40, 41, 42, 43, 44] lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] crc_extra = 195 unpacker = struct.Struct('<QQQQQQQQQQQffffffffffffffffIfihBBBBBBBBBBBBBB') instance_field = None instance_offset = -1 def __init__(self, timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, shutdown_ts, shutdown_alt, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, dpl_bay_max_pressure_ts, dpl_bay_max_pressure, ref_lat, ref_lon, ref_alt, cpu_load, free_heap, ada_state, abk_state, nas_state, mea_state, exp_angle, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, 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.timestamp = timestamp self.liftoff_ts = liftoff_ts self.liftoff_max_acc_ts = liftoff_max_acc_ts self.liftoff_max_acc = liftoff_max_acc self.max_speed_ts = max_speed_ts self.max_speed = max_speed self.max_speed_altitude = max_speed_altitude self.max_mach_ts = max_mach_ts self.max_mach = max_mach self.shutdown_ts = shutdown_ts self.shutdown_alt = shutdown_alt self.apogee_ts = apogee_ts self.apogee_lat = apogee_lat self.apogee_lon = apogee_lon self.apogee_alt = apogee_alt self.apogee_max_acc_ts = apogee_max_acc_ts self.apogee_max_acc = apogee_max_acc self.dpl_ts = dpl_ts self.dpl_alt = dpl_alt self.dpl_max_acc_ts = dpl_max_acc_ts self.dpl_max_acc = dpl_max_acc self.dpl_bay_max_pressure_ts = dpl_bay_max_pressure_ts self.dpl_bay_max_pressure = dpl_bay_max_pressure self.ref_lat = ref_lat self.ref_lon = ref_lon self.ref_alt = ref_alt self.cpu_load = cpu_load self.free_heap = free_heap self.ada_state = ada_state self.abk_state = abk_state self.nas_state = nas_state self.mea_state = mea_state self.exp_angle = exp_angle self.pin_launch = pin_launch self.pin_nosecone = pin_nosecone self.pin_expulsion = pin_expulsion self.cutter_presence = cutter_presence self.log_number = log_number self.log_good = log_good self.payload_board_state = payload_board_state self.motor_board_state = motor_board_state self.payload_can_status = payload_can_status self.motor_can_status = motor_can_status self.rig_can_status = rig_can_status self.hil_state = hil_state def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 195, struct.pack('<QQQQQQQQQQQffffffffffffffffIfihBBBBBBBBBBBBBB', self.timestamp, self.liftoff_ts, self.liftoff_max_acc_ts, self.max_speed_ts, self.max_mach_ts, self.shutdown_ts, self.apogee_ts, self.apogee_max_acc_ts, self.dpl_ts, self.dpl_max_acc_ts, self.dpl_bay_max_pressure_ts, self.liftoff_max_acc, self.max_speed, self.max_speed_altitude, self.max_mach, self.shutdown_alt, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.apogee_max_acc, self.dpl_alt, self.dpl_max_acc, self.dpl_bay_max_pressure, self.ref_lat, self.ref_lon, self.ref_alt, self.cpu_load, self.free_heap, self.exp_angle, self.log_good, self.log_number, self.ada_state, self.abk_state, self.nas_state, self.mea_state, self.pin_launch, self.pin_nosecone, self.pin_expulsion, self.cutter_presence, self.payload_board_state, self.motor_board_state, self.payload_can_status, self.motor_can_status, self.rig_can_status, self.hil_state), force_mavlink1=force_mavlink1) class MAVLink_payload_stats_tm_message(MAVLink_message): ''' Low Rate Payload Telemetry ''' id = MAVLINK_MSG_ID_PAYLOAD_STATS_TM name = 'PAYLOAD_STATS_TM' fieldnames = ['timestamp', 'liftoff_ts', 'liftoff_max_acc_ts', 'liftoff_max_acc', 'max_speed_ts', 'max_speed', 'max_speed_altitude', 'max_mach_ts', 'max_mach', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'apogee_max_acc_ts', 'apogee_max_acc', 'wing_target_lat', 'wing_target_lon', 'wing_active_target_n', 'wing_active_target_e', 'wing_algorithm', 'dpl_ts', 'dpl_alt', 'dpl_max_acc_ts', 'dpl_max_acc', 'ref_lat', 'ref_lon', 'ref_alt', 'min_pressure', 'cpu_load', 'free_heap', 'nas_state', 'wnc_state', 'pin_launch', 'pin_nosecone', 'cutter_presence', 'log_number', 'log_good', 'main_board_state', 'motor_board_state', 'main_can_status', 'motor_can_status', 'rig_can_status', 'hil_state'] ordered_fieldnames = ['timestamp', 'liftoff_ts', 'liftoff_max_acc_ts', 'max_speed_ts', 'max_mach_ts', 'apogee_ts', 'apogee_max_acc_ts', 'dpl_ts', 'dpl_max_acc_ts', 'liftoff_max_acc', 'max_speed', 'max_speed_altitude', 'max_mach', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'apogee_max_acc', 'wing_target_lat', 'wing_target_lon', 'wing_active_target_n', 'wing_active_target_e', 'dpl_alt', 'dpl_max_acc', 'ref_lat', 'ref_lon', 'ref_alt', 'min_pressure', 'cpu_load', 'free_heap', 'log_good', 'log_number', 'wing_algorithm', 'nas_state', 'wnc_state', 'pin_launch', 'pin_nosecone', 'cutter_presence', 'main_board_state', 'motor_board_state', 'main_can_status', 'motor_can_status', 'rig_can_status', 'hil_state'] fieldtypes = ['uint64_t', 'uint64_t', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'uint32_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'int16_t', 'int32_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t'] fielddisplays_by_name = {} fieldenums_by_name = {} fieldunits_by_name = {"timestamp": "us", "liftoff_ts": "us", "liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "max_speed_ts": "us", "max_speed": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "apogee_max_acc_ts": "us", "apogee_max_acc": "m/s2", "wing_target_lat": "deg", "wing_target_lon": "deg", "wing_active_target_n": "m", "wing_active_target_e": "m", "dpl_ts": "us", "dpl_alt": "m", "dpl_max_acc_ts": "us", "dpl_max_acc": "m/s2", "ref_lat": "deg", "ref_lon": "deg", "ref_alt": "m", "min_pressure": "Pa"} format = '<QQQQQQQQQfffffffffffffffffffIihBBBBBBBBBBBB' native_format = bytearray('<QQQQQQQQQfffffffffffffffffffIihBBBBBBBBBBBB', 'ascii') orders = [0, 1, 2, 9, 3, 10, 11, 4, 12, 5, 13, 14, 15, 6, 16, 17, 18, 19, 20, 31, 7, 21, 8, 22, 23, 24, 25, 26, 27, 28, 32, 33, 34, 35, 36, 30, 29, 37, 38, 39, 40, 41, 42] 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] 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] crc_extra = 99 unpacker = struct.Struct('<QQQQQQQQQfffffffffffffffffffIihBBBBBBBBBBBB') instance_field = None instance_offset = -1 def __init__(self, timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_target_lat, wing_target_lon, wing_active_target_n, wing_active_target_e, wing_algorithm, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wnc_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state): 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.timestamp = timestamp self.liftoff_ts = liftoff_ts self.liftoff_max_acc_ts = liftoff_max_acc_ts self.liftoff_max_acc = liftoff_max_acc self.max_speed_ts = max_speed_ts self.max_speed = max_speed self.max_speed_altitude = max_speed_altitude self.max_mach_ts = max_mach_ts self.max_mach = max_mach self.apogee_ts = apogee_ts self.apogee_lat = apogee_lat self.apogee_lon = apogee_lon self.apogee_alt = apogee_alt self.apogee_max_acc_ts = apogee_max_acc_ts self.apogee_max_acc = apogee_max_acc self.wing_target_lat = wing_target_lat self.wing_target_lon = wing_target_lon self.wing_active_target_n = wing_active_target_n self.wing_active_target_e = wing_active_target_e self.wing_algorithm = wing_algorithm self.dpl_ts = dpl_ts self.dpl_alt = dpl_alt self.dpl_max_acc_ts = dpl_max_acc_ts self.dpl_max_acc = dpl_max_acc self.ref_lat = ref_lat self.ref_lon = ref_lon self.ref_alt = ref_alt self.min_pressure = min_pressure self.cpu_load = cpu_load self.free_heap = free_heap self.nas_state = nas_state self.wnc_state = wnc_state self.pin_launch = pin_launch self.pin_nosecone = pin_nosecone self.cutter_presence = cutter_presence self.log_number = log_number self.log_good = log_good self.main_board_state = main_board_state self.motor_board_state = motor_board_state self.main_can_status = main_can_status self.motor_can_status = motor_can_status self.rig_can_status = rig_can_status self.hil_state = hil_state def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 99, struct.pack('<QQQQQQQQQfffffffffffffffffffIihBBBBBBBBBBBB', self.timestamp, self.liftoff_ts, self.liftoff_max_acc_ts, self.max_speed_ts, self.max_mach_ts, self.apogee_ts, self.apogee_max_acc_ts, self.dpl_ts, self.dpl_max_acc_ts, self.liftoff_max_acc, self.max_speed, self.max_speed_altitude, self.max_mach, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.apogee_max_acc, self.wing_target_lat, self.wing_target_lon, self.wing_active_target_n, self.wing_active_target_e, self.dpl_alt, self.dpl_max_acc, self.ref_lat, self.ref_lon, self.ref_alt, self.min_pressure, self.cpu_load, self.free_heap, self.log_good, self.log_number, self.wing_algorithm, self.nas_state, self.wnc_state, self.pin_launch, self.pin_nosecone, self.cutter_presence, self.main_board_state, self.motor_board_state, self.main_can_status, self.motor_can_status, self.rig_can_status, self.hil_state), force_mavlink1=force_mavlink1) 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', 'arming_state', 'battery_voltage', 'current_consumption', 'umbilical_current_consumption', 'main_board_state', 'payload_board_state', 'motor_board_state', 'main_can_status', 'payload_can_status', 'motor_can_status', 'log_number', 'log_good'] ordered_fieldnames = ['timestamp', 'loadcell_rocket', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'battery_voltage', 'current_consumption', 'umbilical_current_consumption', 'log_good', 'log_number', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'nitrogen_valve_state', 'gmm_state', 'tars_state', 'arming_state', 'main_board_state', 'payload_board_state', 'motor_board_state', 'main_can_status', 'payload_can_status', 'motor_can_status'] fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'uint8_t', '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', '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 = '<QfffffffihBBBBBBBBBBBBBB' native_format = bytearray('<QfffffffihBBBBBBBBBBBBBB', 'ascii') orders = [0, 1, 2, 3, 4, 10, 11, 12, 13, 14, 15, 16, 17, 5, 6, 7, 18, 19, 20, 21, 22, 23, 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, 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] crc_extra = 33 unpacker = struct.Struct('<QfffffffihBBBBBBBBBBBBBB') 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, arming_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good): MAVLink_message.__init__(self, MAVLink_gse_tm_message.id, MAVLink_gse_tm_message.name) self._fieldnames = MAVLink_gse_tm_message.fieldnames self._instance_field = MAVLink_gse_tm_message.instance_field 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.arming_state = arming_state self.battery_voltage = battery_voltage self.current_consumption = current_consumption self.umbilical_current_consumption = umbilical_current_consumption self.main_board_state = main_board_state self.payload_board_state = payload_board_state self.motor_board_state = motor_board_state 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.log_good = log_good def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 33, struct.pack('<QfffffffihBBBBBBBBBBBBBB', 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.log_good, 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.arming_state, self.main_board_state, self.payload_board_state, self.motor_board_state, self.main_can_status, self.payload_can_status, self.motor_can_status), force_mavlink1=force_mavlink1) class MAVLink_motor_tm_message(MAVLink_message): ''' 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', 'log_good', 'hil_state'] ordered_fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'tank_temperature', 'battery_voltage', 'log_good', '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 = 67 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, log_good, 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.log_good = log_good self.hil_state = hil_state def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 67, struct.pack('<QfffffihBBB', self.timestamp, self.top_tank_pressure, self.bottom_tank_pressure, self.combustion_chamber_pressure, self.tank_temperature, self.battery_voltage, self.log_good, self.log_number, self.main_valve_state, self.venting_valve_state, self.hil_state), force_mavlink1=force_mavlink1) class MAVLink_calibration_tm_message(MAVLink_message): ''' Calibration telemetry ''' id = MAVLINK_MSG_ID_CALIBRATION_TM name = 'CALIBRATION_TM' fieldnames = ['timestamp', 'gyro_bias_x', 'gyro_bias_y', 'gyro_bias_z', 'mag_bias_x', 'mag_bias_y', 'mag_bias_z', 'mag_scale_x', 'mag_scale_y', 'mag_scale_z', 'static_press_1_bias', 'static_press_1_scale', 'static_press_2_bias', 'static_press_2_scale', 'dpl_bay_press_bias', 'dpl_bay_press_scale', 'dynamic_press_bias', 'dynamic_press_scale'] ordered_fieldnames = ['timestamp', 'gyro_bias_x', 'gyro_bias_y', 'gyro_bias_z', 'mag_bias_x', 'mag_bias_y', 'mag_bias_z', 'mag_scale_x', 'mag_scale_y', 'mag_scale_z', 'static_press_1_bias', 'static_press_1_scale', 'static_press_2_bias', 'static_press_2_scale', 'dpl_bay_press_bias', 'dpl_bay_press_scale', 'dynamic_press_bias', 'dynamic_press_scale'] fieldtypes = ['uint64_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", "gyro_bias_x": "deg/s", "gyro_bias_y": "deg/s", "gyro_bias_z": "deg/s", "mag_bias_x": "uT", "mag_bias_y": "uT", "mag_bias_z": "uT", "static_press_1_bias": "Pa", "static_press_2_bias": "Pa", "dpl_bay_press_bias": "Pa", "dynamic_press_bias": "Pa"} format = '<Qfffffffffffffffff' native_format = bytearray('<Qfffffffffffffffff', 'ascii') orders = [0, 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] array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] crc_extra = 210 unpacker = struct.Struct('<Qfffffffffffffffff') instance_field = None instance_offset = -1 def __init__(self, timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale, dynamic_press_bias, dynamic_press_scale): MAVLink_message.__init__(self, MAVLink_calibration_tm_message.id, MAVLink_calibration_tm_message.name) self._fieldnames = MAVLink_calibration_tm_message.fieldnames self._instance_field = MAVLink_calibration_tm_message.instance_field self._instance_offset = MAVLink_calibration_tm_message.instance_offset self.timestamp = timestamp self.gyro_bias_x = gyro_bias_x self.gyro_bias_y = gyro_bias_y self.gyro_bias_z = gyro_bias_z self.mag_bias_x = mag_bias_x self.mag_bias_y = mag_bias_y self.mag_bias_z = mag_bias_z self.mag_scale_x = mag_scale_x self.mag_scale_y = mag_scale_y self.mag_scale_z = mag_scale_z self.static_press_1_bias = static_press_1_bias self.static_press_1_scale = static_press_1_scale self.static_press_2_bias = static_press_2_bias self.static_press_2_scale = static_press_2_scale self.dpl_bay_press_bias = dpl_bay_press_bias self.dpl_bay_press_scale = dpl_bay_press_scale self.dynamic_press_bias = dynamic_press_bias self.dynamic_press_scale = dynamic_press_scale def pack(self, mav, force_mavlink1=False): return MAVLink_message.pack(self, mav, 210, struct.pack('<Qfffffffffffffffff', self.timestamp, self.gyro_bias_x, self.gyro_bias_y, self.gyro_bias_z, self.mag_bias_x, self.mag_bias_y, self.mag_bias_z, self.mag_scale_x, self.mag_scale_y, self.mag_scale_z, self.static_press_1_bias, self.static_press_1_scale, self.static_press_2_bias, self.static_press_2_scale, self.dpl_bay_press_bias, self.dpl_bay_press_scale, self.dynamic_press_bias, self.dynamic_press_scale), force_mavlink1=force_mavlink1) 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_CALIBRATION_PRESSURE_TC : MAVLink_set_calibration_pressure_tc_message, MAVLINK_MSG_ID_SET_INITIAL_MEA_MASS_TC : MAVLink_set_initial_mea_mass_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_SET_STEPPER_MULTIPLIER_TC : MAVLink_set_stepper_multiplier_tc_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_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_REFERENCE_TM : MAVLink_reference_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_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, MAVLINK_MSG_ID_CALIBRATION_TM : MAVLink_calibration_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] 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]) 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]) class MAVLinkSigning(object): '''MAVLink signing state class''' def __init__(self): self.secret_key = None self.timestamp = 0 self.link_id = 0 self.sign_outgoing = False self.allow_unsigned_callback = None self.stream_timestamps = {} 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() 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): '''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() 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): '''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 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: 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): 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:] else: sig1 = str(h.digest())[:6] sig2 = str(msgbuf)[-6:] if sig1 != sig2: # print('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 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 else: signature_len = 0 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)) if not mapkey in mavlink_map: return MAVLink_unknown(msgId, msgbuf) # decode the payload type = mavlink_map[mapkey] fmt = type.format order_map = type.orders len_map = type.lengths crc_extra = type.crc_extra # 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) ''' return MAVLink_ping_tc_message(timestamp) def ping_tc_send(self, timestamp, force_mavlink1=False): ''' TC to ping the rocket (expects an ACK message as a response) timestamp : Timestamp to identify when it was sent (type:uint64_t) ''' return self.send(self.ping_tc_encode(timestamp), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_command_tc_message(command_id) def command_tc_send(self, command_id, force_mavlink1=False): ''' TC containing a command with no parameters that trigger some action command_id : A member of the MavCommandList enum (type:uint8_t) ''' return self.send(self.command_tc_encode(command_id), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_system_tm_request_tc_message(tm_id) def system_tm_request_tc_send(self, tm_id, force_mavlink1=False): ''' TC containing a request for the status of a board tm_id : A member of the SystemTMList enum (type:uint8_t) ''' return self.send(self.system_tm_request_tc_encode(tm_id), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_sensor_tm_request_tc_message(sensor_name) def sensor_tm_request_tc_send(self, sensor_name, force_mavlink1=False): ''' TC containing a request for sensors telemetry sensor_name : A member of the SensorTMList enum (type:uint8_t) ''' return self.send(self.sensor_tm_request_tc_encode(sensor_name), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_servo_tm_request_tc_message(servo_id) 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) ''' return self.send(self.servo_tm_request_tc_encode(servo_id), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_set_servo_angle_tc_message(servo_id, angle) 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) angle : Servo angle in normalized value [0-1] (type:float) ''' return self.send(self.set_servo_angle_tc_encode(servo_id, angle), force_mavlink1=force_mavlink1) def reset_servo_tc_encode(self, servo_id): ''' Resets the specified servo servo_id : A member of the ServosList enum (type:uint8_t) ''' return MAVLink_reset_servo_tc_message(servo_id) 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) ''' return self.send(self.reset_servo_tc_encode(servo_id), force_mavlink1=force_mavlink1) def wiggle_servo_tc_encode(self, servo_id): ''' Wiggles the specified servo servo_id : A member of the ServosList enum (type:uint8_t) ''' return MAVLink_wiggle_servo_tc_message(servo_id) def wiggle_servo_tc_send(self, servo_id, force_mavlink1=False): ''' Wiggles the specified servo servo_id : A member of the ServosList enum (type:uint8_t) ''' return self.send(self.wiggle_servo_tc_encode(servo_id), force_mavlink1=force_mavlink1) def set_reference_altitude_tc_encode(self, ref_altitude): ''' Sets the reference altitude for the altimeter ref_altitude : Reference altitude [m] (type:float) ''' return MAVLink_set_reference_altitude_tc_message(ref_altitude) def set_reference_altitude_tc_send(self, ref_altitude, force_mavlink1=False): ''' Sets the reference altitude for the altimeter ref_altitude : Reference altitude [m] (type:float) ''' return self.send(self.set_reference_altitude_tc_encode(ref_altitude), force_mavlink1=force_mavlink1) def set_reference_temperature_tc_encode(self, ref_temp): ''' Sets the reference temperature for the altimeter ref_temp : Reference temperature [degC] (type:float) ''' return MAVLink_set_reference_temperature_tc_message(ref_temp) def set_reference_temperature_tc_send(self, ref_temp, force_mavlink1=False): ''' Sets the reference temperature for the altimeter ref_temp : Reference temperature [degC] (type:float) ''' return self.send(self.set_reference_temperature_tc_encode(ref_temp), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_set_orientation_tc_message(yaw, pitch, roll) def set_orientation_tc_send(self, yaw, pitch, roll, force_mavlink1=False): ''' 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) ''' return self.send(self.set_orientation_tc_encode(yaw, pitch, roll), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_set_orientation_quat_tc_message(quat_x, quat_y, quat_z, quat_w) 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 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 self.send(self.set_orientation_quat_tc_encode(quat_x, quat_y, quat_z, quat_w), force_mavlink1=force_mavlink1) def set_coordinates_tc_encode(self, latitude, longitude): ''' Sets current coordinates latitude : Latitude [deg] (type:float) longitude : Longitude [deg] (type:float) ''' return MAVLink_set_coordinates_tc_message(latitude, longitude) def set_coordinates_tc_send(self, latitude, longitude, force_mavlink1=False): ''' Sets current coordinates latitude : Latitude [deg] (type:float) longitude : Longitude [deg] (type:float) ''' return self.send(self.set_coordinates_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_raw_event_tc_message(topic_id, event_id) 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 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 self.send(self.raw_event_tc_encode(topic_id, event_id), force_mavlink1=force_mavlink1) def set_deployment_altitude_tc_encode(self, dpl_altitude): ''' Sets the deployment altitude for the main parachute dpl_altitude : Deployment altitude [m] (type:float) ''' return MAVLink_set_deployment_altitude_tc_message(dpl_altitude) def set_deployment_altitude_tc_send(self, dpl_altitude, force_mavlink1=False): ''' Sets the deployment altitude for the main parachute dpl_altitude : Deployment altitude [m] (type:float) ''' return self.send(self.set_deployment_altitude_tc_encode(dpl_altitude), force_mavlink1=force_mavlink1) def set_target_coordinates_tc_encode(self, latitude, longitude): ''' Sets the target coordinates latitude : Latitude [deg] (type:float) longitude : Longitude [deg] (type:float) ''' return MAVLink_set_target_coordinates_tc_message(latitude, longitude) def set_target_coordinates_tc_send(self, latitude, longitude, force_mavlink1=False): ''' Sets the target coordinates latitude : Latitude [deg] (type:float) longitude : Longitude [deg] (type:float) ''' return self.send(self.set_target_coordinates_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1) def set_algorithm_tc_encode(self, algorithm_number): ''' Sets the algorithm number (for parafoil guidance) algorithm_number : Algorithm number (type:uint8_t) ''' return MAVLink_set_algorithm_tc_message(algorithm_number) def set_algorithm_tc_send(self, algorithm_number, force_mavlink1=False): ''' Sets the algorithm number (for parafoil guidance) algorithm_number : Algorithm number (type:uint8_t) ''' return self.send(self.set_algorithm_tc_encode(algorithm_number), force_mavlink1=force_mavlink1) def set_calibration_pressure_tc_encode(self, pressure): ''' Set the pressure used for analog pressure calibration pressure : Pressure [Pa] (type:float) ''' return MAVLink_set_calibration_pressure_tc_message(pressure) def set_calibration_pressure_tc_send(self, pressure, force_mavlink1=False): ''' Set the pressure used for analog pressure calibration pressure : Pressure [Pa] (type:float) ''' return self.send(self.set_calibration_pressure_tc_encode(pressure), force_mavlink1=force_mavlink1) def set_initial_mea_mass_tc_encode(self, mass): ''' Set the initial MEA mass mass : Mass [kg] (type:float) ''' return MAVLink_set_initial_mea_mass_tc_message(mass) def set_initial_mea_mass_tc_send(self, mass, force_mavlink1=False): ''' Set the initial MEA mass mass : Mass [kg] (type:float) ''' return self.send(self.set_initial_mea_mass_tc_encode(mass), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_set_atomic_valve_timing_tc_message(servo_id, maximum_timing) 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_timing : Maximum timing in [ms] [ms] (type:uint32_t) ''' return self.send(self.set_atomic_valve_timing_tc_encode(servo_id, maximum_timing), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_set_valve_maximum_aperture_tc_message(servo_id, maximum_aperture) 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 servo_id : A member of the ServosList enum (type:uint8_t) maximum_aperture : Maximum aperture (type:float) ''' return self.send(self.set_valve_maximum_aperture_tc_encode(servo_id, maximum_aperture), force_mavlink1=force_mavlink1) 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) ''' 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 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 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 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_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) ''' return MAVLink_set_ignition_time_tc_message(timing) 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) ''' return self.send(self.set_ignition_time_tc_encode(timing), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_set_nitrogen_time_tc_message(timing) 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) ''' return self.send(self.set_nitrogen_time_tc_encode(timing), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_set_cooling_time_tc_message(timing) 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 timing : Timing in [ms] [ms] (type:uint32_t) ''' return self.send(self.set_cooling_time_tc_encode(timing), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_set_stepper_angle_tc_message(stepper_id, angle) 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) angle : Stepper angle in degrees (type:float) ''' return self.send(self.set_stepper_angle_tc_encode(stepper_id, angle), force_mavlink1=force_mavlink1) 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) ''' return MAVLink_set_stepper_steps_tc_message(stepper_id, steps) def set_stepper_steps_tc_send(self, stepper_id, steps, force_mavlink1=False): ''' 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) ''' return self.send(self.set_stepper_steps_tc_encode(stepper_id, steps), force_mavlink1=force_mavlink1) def set_stepper_multiplier_tc_encode(self, stepper_id, multiplier): ''' Set the multiplier of the stepper stepper_id : A member of the StepperList enum (type:uint8_t) multiplier : Multiplier (type:float) ''' return MAVLink_set_stepper_multiplier_tc_message(stepper_id, multiplier) def set_stepper_multiplier_tc_send(self, stepper_id, multiplier, force_mavlink1=False): ''' Set the multiplier of the stepper stepper_id : A member of the StepperList enum (type:uint8_t) multiplier : Multiplier (type:float) ''' return self.send(self.set_stepper_multiplier_tc_encode(stepper_id, multiplier), force_mavlink1=force_mavlink1) def set_antenna_coordinates_arp_tc_encode(self, latitude, longitude, height): ''' Sets current antennas coordinates latitude : Latitude [deg] (type:float) longitude : Longitude [deg] (type:float) height : Height [m] (type:float) ''' return MAVLink_set_antenna_coordinates_arp_tc_message(latitude, longitude, height) def set_antenna_coordinates_arp_tc_send(self, latitude, longitude, height, force_mavlink1=False): ''' Sets current antennas coordinates latitude : Latitude [deg] (type:float) longitude : Longitude [deg] (type:float) height : Height [m] (type:float) ''' return self.send(self.set_antenna_coordinates_arp_tc_encode(latitude, longitude, height), force_mavlink1=force_mavlink1) def set_rocket_coordinates_arp_tc_encode(self, latitude, longitude, height): ''' 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, longitude, height, force_mavlink1=False): ''' Sets current rocket coordinates latitude : Latitude [deg] (type:float) longitude : Longitude [deg] (type:float) height : Height [m] (type:float) ''' return self.send(self.set_rocket_coordinates_arp_tc_encode(latitude, longitude, height), force_mavlink1=force_mavlink1) def arp_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) ''' return MAVLink_arp_command_tc_message(command_id) def arp_command_tc_send(self, command_id, force_mavlink1=False): ''' TC containing a command with no parameters that trigger some action command_id : A member of the MavCommandList enum (type:uint8_t) ''' return self.send(self.arp_command_tc_encode(command_id), force_mavlink1=force_mavlink1) def ack_tm_encode(self, recv_msgid, seq_ack): ''' 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, seq_ack, force_mavlink1=False): ''' 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 self.send(self.ack_tm_encode(recv_msgid, seq_ack), force_mavlink1=force_mavlink1) 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) def load_tm_send(self, timestamp, sensor_name, load, force_mavlink1=False): ''' 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): ''' 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_attitude_tm_message(timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w) def attitude_tm_send(self, timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w, force_mavlink1=False): ''' 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 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 sensor_state_tm_encode(self, sensor_name, initialized, enabled): ''' 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_sensor_state_tm_message(sensor_name, initialized, enabled) def sensor_state_tm_send(self, sensor_name, initialized, enabled, force_mavlink1=False): ''' 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 self.send(self.sensor_state_tm_encode(sensor_name, initialized, enabled), force_mavlink1=force_mavlink1) def servo_tm_encode(self, servo_id, servo_position): ''' servo_id : A member of the ServosList enum (type:uint8_t) servo_position : Position of the servo [0-1] (type:float) ''' 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 reference_tm_encode(self, timestamp, ref_altitude, ref_pressure, ref_temperature, ref_latitude, ref_longitude, msl_pressure, msl_temperature): ''' timestamp : Timestamp [us] (type:uint64_t) ref_altitude : Reference altitude [m] (type:float) ref_pressure : Reference atmospheric pressure [Pa] (type:float) ref_temperature : Reference temperature [degC] (type:float) ref_latitude : Reference latitude [deg] (type:float) ref_longitude : Reference longitude [deg] (type:float) msl_pressure : Mean sea level atmospheric pressure [Pa] (type:float) msl_temperature : Mean sea level temperature [degC] (type:float) ''' return MAVLink_reference_tm_message(timestamp, ref_altitude, ref_pressure, ref_temperature, ref_latitude, ref_longitude, msl_pressure, msl_temperature) def reference_tm_send(self, timestamp, ref_altitude, ref_pressure, ref_temperature, ref_latitude, ref_longitude, msl_pressure, msl_temperature, force_mavlink1=False): ''' timestamp : Timestamp [us] (type:uint64_t) ref_altitude : Reference altitude [m] (type:float) ref_pressure : Reference atmospheric pressure [Pa] (type:float) ref_temperature : Reference temperature [degC] (type:float) ref_latitude : Reference latitude [deg] (type:float) ref_longitude : Reference longitude [deg] (type:float) msl_pressure : Mean sea level atmospheric pressure [Pa] (type:float) msl_temperature : Mean sea level temperature [degC] (type:float) ''' return self.send(self.reference_tm_encode(timestamp, ref_altitude, ref_pressure, ref_temperature, ref_latitude, ref_longitude, msl_pressure, msl_temperature), 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, 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): ''' 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, state, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, ethernet_present, ethernet_status, battery_voltage, log_number, force_mavlink1=False): ''' 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 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 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, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, mea_apogee, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, vn100_qx, vn100_qy, vn100_qz, vn100_qw, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, 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): ''' High Rate Rocket Telemetry timestamp : Timestamp in microseconds [us] (type:uint64_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) mea_apogee : MEA estimated apogee [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) vn100_qx : VN100 estimated attitude (qx) (type:float) vn100_qy : VN100 estimated attitude (qy) (type:float) vn100_qz : VN100 estimated attitude (qz) (type:float) vn100_qw : VN100 estimated attitude (qw) (type:float) gps_fix : Wether the GPS has a FIX (type:uint8_t) gps_lat : Latitude [deg] (type:float) gps_lon : Longitude [deg] (type:float) gps_alt : GPS Altitude [m] (type:float) fmm_state : Flight Mode Manager State (type:uint8_t) abk_angle : Air Brakes angle (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) (type:float) nas_qy : NAS estimated attitude (qy) (type:float) nas_qz : NAS estimated attitude (qz) (type:float) nas_qw : NAS estimated attitude (qw) (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) battery_voltage : Battery voltage [V] (type:float) cam_battery_voltage : Camera battery voltage [V] (type:float) temperature : Temperature [degC] (type:float) ''' return MAVLink_rocket_flight_tm_message(timestamp, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, mea_apogee, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, vn100_qx, vn100_qy, vn100_qz, vn100_qw, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, 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) def rocket_flight_tm_send(self, timestamp, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, mea_apogee, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, vn100_qx, vn100_qy, vn100_qz, vn100_qw, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, 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, force_mavlink1=False): ''' High Rate Rocket Telemetry timestamp : Timestamp in microseconds [us] (type:uint64_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) mea_apogee : MEA estimated apogee [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) vn100_qx : VN100 estimated attitude (qx) (type:float) vn100_qy : VN100 estimated attitude (qy) (type:float) vn100_qz : VN100 estimated attitude (qz) (type:float) vn100_qw : VN100 estimated attitude (qw) (type:float) gps_fix : Wether the GPS has a FIX (type:uint8_t) gps_lat : Latitude [deg] (type:float) gps_lon : Longitude [deg] (type:float) gps_alt : GPS Altitude [m] (type:float) fmm_state : Flight Mode Manager State (type:uint8_t) abk_angle : Air Brakes angle (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) (type:float) nas_qy : NAS estimated attitude (qy) (type:float) nas_qz : NAS estimated attitude (qz) (type:float) nas_qw : NAS estimated attitude (qw) (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) battery_voltage : Battery voltage [V] (type:float) cam_battery_voltage : Camera battery voltage [V] (type:float) temperature : Temperature [degC] (type:float) ''' return self.send(self.rocket_flight_tm_encode(timestamp, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, mea_apogee, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, vn100_qx, vn100_qy, vn100_qz, vn100_qw, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, 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), force_mavlink1=force_mavlink1) def payload_flight_tm_encode(self, timestamp, pressure_digi, pressure_static, pressure_dynamic, 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, fmm_state, 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): ''' High Rate Payload Telemetry timestamp : Timestamp in microseconds [us] (type:uint64_t) pressure_digi : Pressure from digital sensor [Pa] (type:float) pressure_static : Pressure from static port [Pa] (type:float) pressure_dynamic : Pressure from dynamic 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 : Wether the GPS has a FIX (type:uint8_t) gps_lat : Latitude [deg] (type:float) gps_lon : Longitude [deg] (type:float) gps_alt : GPS Altitude [m] (type:float) fmm_state : Flight Mode Manager State (type:uint8_t) 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) (type:float) nas_qy : NAS estimated attitude (qy) (type:float) nas_qz : NAS estimated attitude (qz) (type:float) nas_qw : NAS estimated attitude (qw) (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) battery_voltage : Battery voltage [V] (type:float) cam_battery_voltage : Camera battery voltage [V] (type:float) temperature : Temperature [degC] (type:float) ''' return MAVLink_payload_flight_tm_message(timestamp, pressure_digi, pressure_static, pressure_dynamic, 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, fmm_state, 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) def payload_flight_tm_send(self, timestamp, pressure_digi, pressure_static, pressure_dynamic, 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, fmm_state, 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, force_mavlink1=False): ''' High Rate Payload Telemetry timestamp : Timestamp in microseconds [us] (type:uint64_t) pressure_digi : Pressure from digital sensor [Pa] (type:float) pressure_static : Pressure from static port [Pa] (type:float) pressure_dynamic : Pressure from dynamic 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 : Wether the GPS has a FIX (type:uint8_t) gps_lat : Latitude [deg] (type:float) gps_lon : Longitude [deg] (type:float) gps_alt : GPS Altitude [m] (type:float) fmm_state : Flight Mode Manager State (type:uint8_t) 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) (type:float) nas_qy : NAS estimated attitude (qy) (type:float) nas_qz : NAS estimated attitude (qz) (type:float) nas_qw : NAS estimated attitude (qw) (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) battery_voltage : Battery voltage [V] (type:float) cam_battery_voltage : Camera battery voltage [V] (type:float) temperature : Temperature [degC] (type:float) ''' return self.send(self.payload_flight_tm_encode(timestamp, pressure_digi, pressure_static, pressure_dynamic, 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, fmm_state, 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), force_mavlink1=force_mavlink1) def rocket_stats_tm_encode(self, timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, shutdown_ts, shutdown_alt, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, dpl_bay_max_pressure_ts, dpl_bay_max_pressure, ref_lat, ref_lon, ref_alt, cpu_load, free_heap, ada_state, abk_state, nas_state, mea_state, exp_angle, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, hil_state): ''' Low Rate Rocket Telemetry timestamp : Timestamp in microseconds [us] (type:uint64_t) 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) max_speed_ts : System clock at max speed [us] (type:uint64_t) max_speed : Max measured speed [m/s] (type:float) max_speed_altitude : Altitude at max speed [m] (type:float) max_mach_ts : System clock at maximum measured mach (type:uint64_t) max_mach : Maximum measured mach (type:float) shutdown_ts : System clock at shutdown (type:uint64_t) shutdown_alt : Altitude at shutdown (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) apogee_max_acc_ts : System clock at max acceleration after apogee [us] (type:uint64_t) apogee_max_acc : Max acceleration after apogee [m/s2] (type:float) dpl_ts : System clock at main deployment [us] (type:uint64_t) dpl_alt : Deployment altitude [m] (type:float) dpl_max_acc_ts : System clock at max acceleration during main deployment [us] (type:uint64_t) dpl_max_acc : Max acceleration during main deployment [m/s2] (type:float) dpl_bay_max_pressure_ts : System clock at max pressure in the deployment bay during drogue deployment [us] (type:uint64_t) dpl_bay_max_pressure : Max pressure in the deployment bay during drogue deployment [Pa] (type:float) ref_lat : Reference altitude [deg] (type:float) ref_lon : Reference longitude [deg] (type:float) ref_alt : Reference altitude [m] (type:float) cpu_load : CPU load in percentage (type:float) free_heap : Amount of available heap in memory (type:uint32_t) ada_state : ADA 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) exp_angle : Expulsion servo angle (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) log_number : Currently active log file, -1 if the logger is inactive (type:int16_t) log_good : 0 if log failed, 1 otherwise (type:int32_t) payload_board_state : Main board fmm state (type:uint8_t) motor_board_state : Motor board fmm state (type:uint8_t) payload_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) hil_state : 1 if the board is currently in HIL mode (type:uint8_t) ''' return MAVLink_rocket_stats_tm_message(timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, shutdown_ts, shutdown_alt, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, dpl_bay_max_pressure_ts, dpl_bay_max_pressure, ref_lat, ref_lon, ref_alt, cpu_load, free_heap, ada_state, abk_state, nas_state, mea_state, exp_angle, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, hil_state) def rocket_stats_tm_send(self, timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, shutdown_ts, shutdown_alt, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, dpl_bay_max_pressure_ts, dpl_bay_max_pressure, ref_lat, ref_lon, ref_alt, cpu_load, free_heap, ada_state, abk_state, nas_state, mea_state, exp_angle, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, hil_state, force_mavlink1=False): ''' Low Rate Rocket Telemetry timestamp : Timestamp in microseconds [us] (type:uint64_t) 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) max_speed_ts : System clock at max speed [us] (type:uint64_t) max_speed : Max measured speed [m/s] (type:float) max_speed_altitude : Altitude at max speed [m] (type:float) max_mach_ts : System clock at maximum measured mach (type:uint64_t) max_mach : Maximum measured mach (type:float) shutdown_ts : System clock at shutdown (type:uint64_t) shutdown_alt : Altitude at shutdown (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) apogee_max_acc_ts : System clock at max acceleration after apogee [us] (type:uint64_t) apogee_max_acc : Max acceleration after apogee [m/s2] (type:float) dpl_ts : System clock at main deployment [us] (type:uint64_t) dpl_alt : Deployment altitude [m] (type:float) dpl_max_acc_ts : System clock at max acceleration during main deployment [us] (type:uint64_t) dpl_max_acc : Max acceleration during main deployment [m/s2] (type:float) dpl_bay_max_pressure_ts : System clock at max pressure in the deployment bay during drogue deployment [us] (type:uint64_t) dpl_bay_max_pressure : Max pressure in the deployment bay during drogue deployment [Pa] (type:float) ref_lat : Reference altitude [deg] (type:float) ref_lon : Reference longitude [deg] (type:float) ref_alt : Reference altitude [m] (type:float) cpu_load : CPU load in percentage (type:float) free_heap : Amount of available heap in memory (type:uint32_t) ada_state : ADA 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) exp_angle : Expulsion servo angle (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) log_number : Currently active log file, -1 if the logger is inactive (type:int16_t) log_good : 0 if log failed, 1 otherwise (type:int32_t) payload_board_state : Main board fmm state (type:uint8_t) motor_board_state : Motor board fmm state (type:uint8_t) payload_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) hil_state : 1 if the board is currently in HIL mode (type:uint8_t) ''' return self.send(self.rocket_stats_tm_encode(timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, shutdown_ts, shutdown_alt, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, dpl_bay_max_pressure_ts, dpl_bay_max_pressure, ref_lat, ref_lon, ref_alt, cpu_load, free_heap, ada_state, abk_state, nas_state, mea_state, exp_angle, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, hil_state), force_mavlink1=force_mavlink1) def payload_stats_tm_encode(self, timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_target_lat, wing_target_lon, wing_active_target_n, wing_active_target_e, wing_algorithm, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wnc_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state): ''' Low Rate Payload Telemetry timestamp : Timestamp in microseconds [us] (type:uint64_t) 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) max_speed_ts : System clock at max speed [us] (type:uint64_t) max_speed : Max measured speed [m/s] (type:float) max_speed_altitude : Altitude at max speed [m] (type:float) max_mach_ts : System clock at maximum measured mach (type:uint64_t) max_mach : Maximum measured mach (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) apogee_max_acc_ts : System clock at max acceleration after apogee [us] (type:uint64_t) apogee_max_acc : Max acceleration after apogee [m/s2] (type:float) wing_target_lat : Wing target latitude [deg] (type:float) wing_target_lon : Wing target longitude [deg] (type:float) wing_active_target_n : Wing active target N [m] (type:float) wing_active_target_e : Wing active target E [m] (type:float) wing_algorithm : Wing selected algorithm (type:uint8_t) dpl_ts : System clock at main deployment [us] (type:uint64_t) dpl_alt : Deployment altitude [m] (type:float) dpl_max_acc_ts : System clock at max acceleration during main deployment [us] (type:uint64_t) dpl_max_acc : Max acceleration during main deployment [m/s2] (type:float) ref_lat : Reference altitude [deg] (type:float) ref_lon : Reference longitude [deg] (type:float) ref_alt : Reference 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) nas_state : NAS FSM State (type:uint8_t) wnc_state : Wing Controller State (type:uint8_t) pin_launch : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t) pin_nosecone : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t) cutter_presence : Cutter presence status (1 = present, 0 = missing) (type:uint8_t) log_number : Currently active log file, -1 if the logger is inactive (type:int16_t) log_good : 0 if log failed, 1 otherwise (type:int32_t) main_board_state : Main board fmm state (type:uint8_t) motor_board_state : Motor board fmm state (type:uint8_t) 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) hil_state : 1 if the board is currently in HIL mode (type:uint8_t) ''' return MAVLink_payload_stats_tm_message(timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_target_lat, wing_target_lon, wing_active_target_n, wing_active_target_e, wing_algorithm, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wnc_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state) def payload_stats_tm_send(self, timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_target_lat, wing_target_lon, wing_active_target_n, wing_active_target_e, wing_algorithm, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wnc_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state, force_mavlink1=False): ''' Low Rate Payload Telemetry timestamp : Timestamp in microseconds [us] (type:uint64_t) 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) max_speed_ts : System clock at max speed [us] (type:uint64_t) max_speed : Max measured speed [m/s] (type:float) max_speed_altitude : Altitude at max speed [m] (type:float) max_mach_ts : System clock at maximum measured mach (type:uint64_t) max_mach : Maximum measured mach (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) apogee_max_acc_ts : System clock at max acceleration after apogee [us] (type:uint64_t) apogee_max_acc : Max acceleration after apogee [m/s2] (type:float) wing_target_lat : Wing target latitude [deg] (type:float) wing_target_lon : Wing target longitude [deg] (type:float) wing_active_target_n : Wing active target N [m] (type:float) wing_active_target_e : Wing active target E [m] (type:float) wing_algorithm : Wing selected algorithm (type:uint8_t) dpl_ts : System clock at main deployment [us] (type:uint64_t) dpl_alt : Deployment altitude [m] (type:float) dpl_max_acc_ts : System clock at max acceleration during main deployment [us] (type:uint64_t) dpl_max_acc : Max acceleration during main deployment [m/s2] (type:float) ref_lat : Reference altitude [deg] (type:float) ref_lon : Reference longitude [deg] (type:float) ref_alt : Reference 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) nas_state : NAS FSM State (type:uint8_t) wnc_state : Wing Controller State (type:uint8_t) pin_launch : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t) pin_nosecone : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t) cutter_presence : Cutter presence status (1 = present, 0 = missing) (type:uint8_t) log_number : Currently active log file, -1 if the logger is inactive (type:int16_t) log_good : 0 if log failed, 1 otherwise (type:int32_t) main_board_state : Main board fmm state (type:uint8_t) motor_board_state : Motor board fmm state (type:uint8_t) 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) hil_state : 1 if the board is currently in HIL mode (type:uint8_t) ''' return self.send(self.payload_stats_tm_encode(timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_target_lat, wing_target_lon, wing_active_target_n, wing_active_target_e, wing_algorithm, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wnc_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state), force_mavlink1=force_mavlink1) def gse_tm_encode(self, timestamp, 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, arming_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good): ''' Ground Segment Equipment telemetry 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) arming_state : Arming state (1 if armed, 0 otherwise) (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_state : Main board fmm state (type:uint8_t) payload_board_state : Payload board fmm state (type:uint8_t) motor_board_state : Motor board fmm state (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) log_good : 0 if log failed, 1 otherwise (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, arming_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good) def gse_tm_send(self, timestamp, 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, arming_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good, force_mavlink1=False): ''' Ground Segment Equipment telemetry 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) arming_state : Arming state (1 if armed, 0 otherwise) (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_state : Main board fmm state (type:uint8_t) payload_board_state : Payload board fmm state (type:uint8_t) motor_board_state : Motor board fmm state (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) log_good : 0 if log failed, 1 otherwise (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, arming_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good), force_mavlink1=force_mavlink1) def motor_tm_encode(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, log_good, 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) log_good : 0 if log failed, 1 otherwise (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, log_good, 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, log_good, 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) log_good : 0 if log failed, 1 otherwise (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, log_good, hil_state), force_mavlink1=force_mavlink1) def calibration_tm_encode(self, timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale, dynamic_press_bias, dynamic_press_scale): ''' Calibration telemetry timestamp : Timestamp in microseconds [us] (type:uint64_t) gyro_bias_x : Gyroscope X bias [deg/s] (type:float) gyro_bias_y : Gyroscope Y bias [deg/s] (type:float) gyro_bias_z : Gyroscope Z bias [deg/s] (type:float) mag_bias_x : Magnetometer X bias [uT] (type:float) mag_bias_y : Magnetometer Y bias [uT] (type:float) mag_bias_z : Magnetometer Z bias [uT] (type:float) mag_scale_x : Magnetometer X scale (type:float) mag_scale_y : Magnetometer Y scale (type:float) mag_scale_z : Magnetometer Z scale (type:float) static_press_1_bias : Static pressure 1 bias [Pa] (type:float) static_press_1_scale : Static pressure 1 scale (type:float) static_press_2_bias : Static pressure 2 bias [Pa] (type:float) static_press_2_scale : Static pressure 2 scale (type:float) dpl_bay_press_bias : Deployment bay pressure bias [Pa] (type:float) dpl_bay_press_scale : Deployment bay pressure scale (type:float) dynamic_press_bias : Dynamic pressure bias [Pa] (type:float) dynamic_press_scale : Dynamic pressure scale (type:float) ''' return MAVLink_calibration_tm_message(timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale, dynamic_press_bias, dynamic_press_scale) def calibration_tm_send(self, timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale, dynamic_press_bias, dynamic_press_scale, force_mavlink1=False): ''' Calibration telemetry timestamp : Timestamp in microseconds [us] (type:uint64_t) gyro_bias_x : Gyroscope X bias [deg/s] (type:float) gyro_bias_y : Gyroscope Y bias [deg/s] (type:float) gyro_bias_z : Gyroscope Z bias [deg/s] (type:float) mag_bias_x : Magnetometer X bias [uT] (type:float) mag_bias_y : Magnetometer Y bias [uT] (type:float) mag_bias_z : Magnetometer Z bias [uT] (type:float) mag_scale_x : Magnetometer X scale (type:float) mag_scale_y : Magnetometer Y scale (type:float) mag_scale_z : Magnetometer Z scale (type:float) static_press_1_bias : Static pressure 1 bias [Pa] (type:float) static_press_1_scale : Static pressure 1 scale (type:float) static_press_2_bias : Static pressure 2 bias [Pa] (type:float) static_press_2_scale : Static pressure 2 scale (type:float) dpl_bay_press_bias : Deployment bay pressure bias [Pa] (type:float) dpl_bay_press_scale : Deployment bay pressure scale (type:float) dynamic_press_bias : Dynamic pressure bias [Pa] (type:float) dynamic_press_scale : Dynamic pressure scale (type:float) ''' return self.send(self.calibration_tm_encode(timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale, dynamic_press_bias, dynamic_press_scale), force_mavlink1=force_mavlink1)