From c77379f94014df1e5385434dc2374b6c7f40bc4a Mon Sep 17 00:00:00 2001 From: Matteo Pignataro <matteo.pignataro@skywarder.eu> Date: Mon, 28 Aug 2023 16:55:01 +0000 Subject: [PATCH] [Gemini] Aligned telemetry with project requirements --- mavlink_lib.py | 246 ++++-- mavlink_lib/gemini/gemini.h | 39 +- mavlink_lib/gemini/mavlink.h | 2 +- mavlink_lib/gemini/mavlink_msg_mea_tm.h | 363 +++++++++ mavlink_lib/gemini/mavlink_msg_motor_tm.h | 118 ++- .../gemini/mavlink_msg_payload_flight_tm.h | 201 ++--- .../gemini/mavlink_msg_rocket_flight_tm.h | 732 +++++++++--------- mavlink_lib/gemini/testsuite.h | 103 ++- mavlink_lib/gemini/version.h | 4 +- message_definitions/gemini.xml | 49 +- 10 files changed, 1243 insertions(+), 614 deletions(-) create mode 100644 mavlink_lib/gemini/mavlink_msg_mea_tm.h diff --git a/mavlink_lib.py b/mavlink_lib.py index 1494d9e..3881bf5 100644 --- a/mavlink_lib.py +++ b/mavlink_lib.py @@ -266,6 +266,17 @@ class EnumEntry(object): enums = {} +# SysIDs +enums['SysIDs'] = {} +MAIN = 1 # +enums['SysIDs'][1] = EnumEntry('MAIN', '''''') +PAYLOAD = 2 # +enums['SysIDs'][2] = EnumEntry('PAYLOAD', '''''') +RIG = 3 # +enums['SysIDs'][3] = EnumEntry('RIG', '''''') +SysIDs_ENUM_END = 4 # +enums['SysIDs'][4] = EnumEntry('SysIDs_ENUM_END', '''''') + # SystemTMList enums['SystemTMList'] = {} MAV_SYS_ID = 1 # State of init results about system hardware/software components @@ -285,20 +296,20 @@ MAV_ADA_ID = 7 # ADA Status enums['SystemTMList'][7] = EnumEntry('MAV_ADA_ID', '''ADA Status''') MAV_NAS_ID = 8 # NavigationSystem data enums['SystemTMList'][8] = EnumEntry('MAV_NAS_ID', '''NavigationSystem data''') -MAV_CAN_ID = 9 # Canbus stats -enums['SystemTMList'][9] = EnumEntry('MAV_CAN_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_TARS_ID = 15 # TARS data -enums['SystemTMList'][15] = EnumEntry('MAV_TARS_ID', '''TARS data''') +MAV_MEA_ID = 9 # MEA Status +enums['SystemTMList'][9] = EnumEntry('MAV_MEA_ID', '''MEA Status''') +MAV_CAN_ID = 10 # Canbus stats +enums['SystemTMList'][10] = EnumEntry('MAV_CAN_ID', '''Canbus stats''') +MAV_FLIGHT_ID = 11 # Flight telemetry +enums['SystemTMList'][11] = EnumEntry('MAV_FLIGHT_ID', '''Flight telemetry''') +MAV_STATS_ID = 12 # Satistics telemetry +enums['SystemTMList'][12] = EnumEntry('MAV_STATS_ID', '''Satistics telemetry''') +MAV_SENSORS_STATE_ID = 13 # Sensors init state telemetry +enums['SystemTMList'][13] = EnumEntry('MAV_SENSORS_STATE_ID', '''Sensors init state telemetry''') +MAV_GSE_ID = 14 # Ground Segnement Equipment +enums['SystemTMList'][14] = EnumEntry('MAV_GSE_ID', '''Ground Segnement Equipment''') +MAV_MOTOR_ID = 15 # Rocket Motor data +enums['SystemTMList'][15] = EnumEntry('MAV_MOTOR_ID', '''Rocket Motor data''') SystemTMList_ENUM_END = 16 # enums['SystemTMList'][16] = EnumEntry('SystemTMList_ENUM_END', '''''') @@ -483,6 +494,7 @@ MAVLINK_MSG_ID_MAVLINK_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 @@ -1992,29 +2004,67 @@ class MAVLink_nas_tm_message(MAVLink_message): 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": "kg"} + 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 Telemetry ''' id = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM name = 'ROCKET_FLIGHT_TM' - fieldnames = ['timestamp', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'abk_estimated_cd', 'parachute_load', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'estimated_thrust', 'vbat', 'temperature', 'logger_error'] - ordered_fieldnames = ['timestamp', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'abk_estimated_cd', 'parachute_load', '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', 'estimated_thrust', 'vbat', 'temperature', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'gps_fix', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'logger_error'] - fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'int8_t'] + fieldnames = ['timestamp', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'battery_voltage', 'current_consumption', 'temperature', 'logger_error'] + ordered_fieldnames = ['timestamp', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'battery_voltage', 'current_consumption', 'temperature', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'gps_fix', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'logger_error'] + fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'int8_t'] fielddisplays_by_name = {} fieldenums_by_name = {} - fieldunits_by_name = {"timestamp": "us", "pressure_ada": "Pa", "pressure_digi": "Pa", "pressure_static": "Pa", "pressure_dpl": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "ada_vert_speed": "m/s", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "abk_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "vbat": "V", "temperature": "degC"} - format = '<QffffffffffffffffffffffffffffffffffffffBBBBBBBBBBb' - native_format = bytearray('<QffffffffffffffffffffffffffffffffffffffBBBBBBBBBBb', 'ascii') - orders = [0, 39, 40, 41, 42, 43, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 44, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 45, 46, 47, 48, 36, 37, 38, 49] + fieldunits_by_name = {"timestamp": "us", "pressure_ada": "Pa", "pressure_digi": "Pa", "pressure_static": "Pa", "pressure_dpl": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "ada_vert_speed": "m/s", "mea_mass": "kg", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "abk_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "battery_voltage": "V", "current_consumption": "A", "temperature": "degC"} + format = '<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb' + native_format = bytearray('<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb', 'ascii') + orders = [0, 38, 39, 40, 41, 42, 43, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 44, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 45, 46, 47, 48, 35, 36, 37, 49] lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] - crc_extra = 141 - unpacker = struct.Struct('<QffffffffffffffffffffffffffffffffffffffBBBBBBBBBBb') + crc_extra = 254 + unpacker = struct.Struct('<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb') instance_field = None instance_offset = -1 - def __init__(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, abk_estimated_cd, parachute_load, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, estimated_thrust, vbat, temperature, logger_error): + def __init__(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, current_consumption, temperature, logger_error): MAVLink_message.__init__(self, MAVLink_rocket_flight_tm_message.id, MAVLink_rocket_flight_tm_message.name) self._fieldnames = MAVLink_rocket_flight_tm_message.fieldnames self._instance_field = MAVLink_rocket_flight_tm_message.instance_field @@ -2025,6 +2075,7 @@ class MAVLink_rocket_flight_tm_message(MAVLink_message): self.dpl_state = dpl_state self.abk_state = abk_state self.nas_state = nas_state + self.mea_state = mea_state self.pressure_ada = pressure_ada self.pressure_digi = pressure_digi self.pressure_static = pressure_static @@ -2032,6 +2083,7 @@ class MAVLink_rocket_flight_tm_message(MAVLink_message): self.airspeed_pitot = airspeed_pitot self.altitude_agl = altitude_agl self.ada_vert_speed = ada_vert_speed + self.mea_mass = mea_mass self.acc_x = acc_x self.acc_y = acc_y self.acc_z = acc_z @@ -2046,8 +2098,6 @@ class MAVLink_rocket_flight_tm_message(MAVLink_message): self.gps_lon = gps_lon self.gps_alt = gps_alt self.abk_angle = abk_angle - self.abk_estimated_cd = abk_estimated_cd - self.parachute_load = parachute_load self.nas_n = nas_n self.nas_e = nas_e self.nas_d = nas_d @@ -2065,13 +2115,13 @@ class MAVLink_rocket_flight_tm_message(MAVLink_message): self.pin_nosecone = pin_nosecone self.pin_expulsion = pin_expulsion self.cutter_presence = cutter_presence - self.estimated_thrust = estimated_thrust - self.vbat = vbat + self.battery_voltage = battery_voltage + self.current_consumption = current_consumption self.temperature = temperature self.logger_error = logger_error def pack(self, mav, force_mavlink1=False): - return MAVLink_message.pack(self, mav, 141, struct.pack('<QffffffffffffffffffffffffffffffffffffffBBBBBBBBBBb', 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.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.abk_angle, self.abk_estimated_cd, self.parachute_load, 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.estimated_thrust, self.vbat, self.temperature, self.ada_state, self.fmm_state, self.dpl_state, self.abk_state, self.nas_state, self.gps_fix, self.pin_launch, self.pin_nosecone, self.pin_expulsion, self.cutter_presence, self.logger_error), force_mavlink1=force_mavlink1) + return MAVLink_message.pack(self, mav, 254, struct.pack('<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb', self.timestamp, self.pressure_ada, self.pressure_digi, self.pressure_static, self.pressure_dpl, self.airspeed_pitot, self.altitude_agl, self.ada_vert_speed, self.mea_mass, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.abk_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.battery_voltage, self.current_consumption, self.temperature, self.ada_state, self.fmm_state, self.dpl_state, self.abk_state, self.nas_state, self.mea_state, self.gps_fix, self.pin_launch, self.pin_nosecone, self.pin_expulsion, self.cutter_presence, self.logger_error), force_mavlink1=force_mavlink1) class MAVLink_payload_flight_tm_message(MAVLink_message): ''' @@ -2079,23 +2129,23 @@ class MAVLink_payload_flight_tm_message(MAVLink_message): ''' id = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM name = 'PAYLOAD_FLIGHT_TM' - fieldnames = ['timestamp', 'fmm_state', 'nas_state', 'wes_state', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'pin_nosecone', 'vbat', 'vsupply_5v', 'temperature', 'logger_error'] - ordered_fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'vbat', 'vsupply_5v', 'temperature', 'fmm_state', 'nas_state', 'wes_state', 'gps_fix', 'pin_nosecone', 'logger_error'] - fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'int8_t'] + fieldnames = ['timestamp', 'fmm_state', 'nas_state', 'wes_state', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'pin_nosecone', 'battery_voltage', 'current_consumption', 'vsupply_5v', 'temperature', 'logger_error'] + ordered_fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'battery_voltage', 'current_consumption', 'vsupply_5v', 'temperature', 'fmm_state', 'nas_state', 'wes_state', 'gps_fix', 'pin_nosecone', 'logger_error'] + fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'int8_t'] fielddisplays_by_name = {} fieldenums_by_name = {} - fieldunits_by_name = {"timestamp": "us", "pressure_digi": "Pa", "pressure_static": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "left_servo_angle": "deg", "right_servo_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "wes_n": "m/s", "wes_e": "m/s", "vbat": "V", "vsupply_5v": "V", "temperature": "degC"} - format = '<QffffffffffffffffffffffffffffffffffffBBBBBb' - native_format = bytearray('<QffffffffffffffffffffffffffffffffffffBBBBBb', 'ascii') - orders = [0, 37, 38, 39, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 40, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 41, 34, 35, 36, 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 = 229 - unpacker = struct.Struct('<QffffffffffffffffffffffffffffffffffffBBBBBb') + fieldunits_by_name = {"timestamp": "us", "pressure_digi": "Pa", "pressure_static": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "left_servo_angle": "deg", "right_servo_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "wes_n": "m/s", "wes_e": "m/s", "battery_voltage": "V", "current_consumption": "A", "vsupply_5v": "V", "temperature": "degC"} + format = '<QfffffffffffffffffffffffffffffffffffffBBBBBb' + native_format = bytearray('<QfffffffffffffffffffffffffffffffffffffBBBBBb', 'ascii') + orders = [0, 38, 39, 40, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 41, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 42, 34, 35, 36, 37, 43] + 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] + 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] + crc_extra = 117 + unpacker = struct.Struct('<QfffffffffffffffffffffffffffffffffffffBBBBBb') instance_field = None instance_offset = -1 - def __init__(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, vbat, vsupply_5v, temperature, logger_error): + def __init__(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, current_consumption, vsupply_5v, temperature, logger_error): MAVLink_message.__init__(self, MAVLink_payload_flight_tm_message.id, MAVLink_payload_flight_tm_message.name) self._fieldnames = MAVLink_payload_flight_tm_message.fieldnames self._instance_field = MAVLink_payload_flight_tm_message.instance_field @@ -2139,13 +2189,14 @@ class MAVLink_payload_flight_tm_message(MAVLink_message): self.wes_n = wes_n self.wes_e = wes_e self.pin_nosecone = pin_nosecone - self.vbat = vbat + self.battery_voltage = battery_voltage + self.current_consumption = current_consumption self.vsupply_5v = vsupply_5v self.temperature = temperature self.logger_error = logger_error def pack(self, mav, force_mavlink1=False): - return MAVLink_message.pack(self, mav, 229, struct.pack('<QffffffffffffffffffffffffffffffffffffBBBBBb', self.timestamp, self.pressure_digi, self.pressure_static, self.airspeed_pitot, self.altitude_agl, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.left_servo_angle, self.right_servo_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.wes_n, self.wes_e, self.vbat, self.vsupply_5v, self.temperature, self.fmm_state, self.nas_state, self.wes_state, self.gps_fix, self.pin_nosecone, self.logger_error), force_mavlink1=force_mavlink1) + return MAVLink_message.pack(self, mav, 117, struct.pack('<QfffffffffffffffffffffffffffffffffffffBBBBBb', self.timestamp, self.pressure_digi, self.pressure_static, self.airspeed_pitot, self.altitude_agl, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.left_servo_angle, self.right_servo_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.wes_n, self.wes_e, self.battery_voltage, self.current_consumption, self.vsupply_5v, self.temperature, self.fmm_state, self.nas_state, self.wes_state, self.gps_fix, self.pin_nosecone, self.logger_error), force_mavlink1=force_mavlink1) class MAVLink_rocket_stats_tm_message(MAVLink_message): ''' @@ -2296,23 +2347,23 @@ class MAVLink_motor_tm_message(MAVLink_message): ''' id = MAVLINK_MSG_ID_MOTOR_TM name = 'MOTOR_TM' - fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'floating_level', 'tank_temperature', 'main_valve_state'] - ordered_fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'tank_temperature', 'floating_level', 'main_valve_state'] - fieldtypes = ['uint64_t', 'float', 'float', 'float', 'uint8_t', 'float', 'uint8_t'] + fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'floating_level', 'tank_temperature', 'main_valve_state', 'battery_voltage', 'current_consumption'] + ordered_fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'tank_temperature', 'battery_voltage', 'current_consumption', 'floating_level', 'main_valve_state'] + fieldtypes = ['uint64_t', 'float', 'float', 'float', 'uint8_t', 'float', 'uint8_t', 'float', 'float'] fielddisplays_by_name = {} fieldenums_by_name = {} - fieldunits_by_name = {"timestamp": "us", "top_tank_pressure": "Bar", "bottom_tank_pressure": "Bar", "combustion_chamber_pressure": "Bar"} - format = '<QffffBB' - native_format = bytearray('<QffffBB', 'ascii') - orders = [0, 1, 2, 3, 5, 4, 6] - lengths = [1, 1, 1, 1, 1, 1, 1] - array_lengths = [0, 0, 0, 0, 0, 0, 0] - crc_extra = 241 - unpacker = struct.Struct('<QffffBB') + fieldunits_by_name = {"timestamp": "us", "top_tank_pressure": "Bar", "bottom_tank_pressure": "Bar", "combustion_chamber_pressure": "Bar", "battery_voltage": "V", "current_consumption": "A"} + format = '<QffffffBB' + native_format = bytearray('<QffffffBB', 'ascii') + orders = [0, 1, 2, 3, 7, 4, 8, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 196 + unpacker = struct.Struct('<QffffffBB') instance_field = None instance_offset = -1 - def __init__(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state): + def __init__(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, battery_voltage, current_consumption): 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 @@ -2324,9 +2375,11 @@ class MAVLink_motor_tm_message(MAVLink_message): self.floating_level = floating_level self.tank_temperature = tank_temperature self.main_valve_state = main_valve_state + self.battery_voltage = battery_voltage + self.current_consumption = current_consumption def pack(self, mav, force_mavlink1=False): - return MAVLink_message.pack(self, mav, 241, struct.pack('<QffffBB', self.timestamp, self.top_tank_pressure, self.bottom_tank_pressure, self.combustion_chamber_pressure, self.tank_temperature, self.floating_level, self.main_valve_state), force_mavlink1=force_mavlink1) + return MAVLink_message.pack(self, mav, 196, struct.pack('<QffffffBB', self.timestamp, self.top_tank_pressure, self.bottom_tank_pressure, self.combustion_chamber_pressure, self.tank_temperature, self.battery_voltage, self.current_consumption, self.floating_level, self.main_valve_state), force_mavlink1=force_mavlink1) mavlink_map = { @@ -2372,6 +2425,7 @@ mavlink_map = { 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, @@ -3869,7 +3923,37 @@ class MAVLink(object): ''' 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 rocket_flight_tm_encode(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, abk_estimated_cd, parachute_load, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, estimated_thrust, vbat, temperature, logger_error): + 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 [kg] (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 [kg] (type:float) + + ''' + return self.send(self.mea_tm_encode(timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure), force_mavlink1=force_mavlink1) + + def rocket_flight_tm_encode(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, current_consumption, temperature, logger_error): ''' High Rate Telemetry @@ -3879,6 +3963,7 @@ class MAVLink(object): dpl_state : Deployment Controller State (type:uint8_t) abk_state : Airbrake FSM state (type:uint8_t) nas_state : Navigation System FSM State (type:uint8_t) + mea_state : MEA Controller State (type:uint8_t) pressure_ada : Atmospheric pressure estimated by ADA [Pa] (type:float) pressure_digi : Pressure from digital sensor [Pa] (type:float) pressure_static : Pressure from static port [Pa] (type:float) @@ -3886,6 +3971,7 @@ class MAVLink(object): airspeed_pitot : Pitot airspeed [m/s] (type:float) altitude_agl : Altitude above ground level [m] (type:float) ada_vert_speed : Vertical speed estimated by ADA [m/s] (type:float) + mea_mass : Mass estimated by MEA [kg] (type:float) acc_x : Acceleration on X axis (body) [m/s^2] (type:float) acc_y : Acceleration on Y axis (body) [m/s^2] (type:float) acc_z : Acceleration on Z axis (body) [m/s^2] (type:float) @@ -3900,8 +3986,6 @@ class MAVLink(object): gps_lon : Longitude [deg] (type:float) gps_alt : GPS Altitude [m] (type:float) abk_angle : Air Brakes angle [deg] (type:float) - abk_estimated_cd : Estimated drag coefficient (type:float) - parachute_load : Parachute load cell value (type:float) 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) @@ -3919,15 +4003,15 @@ class MAVLink(object): 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) - estimated_thrust : Estimated thrust from automatic shutdown algorithm (type:float) - vbat : Battery voltage [V] (type:float) + battery_voltage : Battery voltage [V] (type:float) + current_consumption : Battery current [A] (type:float) temperature : Temperature [degC] (type:float) logger_error : Logger error (0 = no error, -1 otherwise) (type:int8_t) ''' - return MAVLink_rocket_flight_tm_message(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, abk_estimated_cd, parachute_load, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, estimated_thrust, vbat, temperature, logger_error) + return MAVLink_rocket_flight_tm_message(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, current_consumption, temperature, logger_error) - def rocket_flight_tm_send(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, abk_estimated_cd, parachute_load, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, estimated_thrust, vbat, temperature, logger_error, force_mavlink1=False): + def rocket_flight_tm_send(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, current_consumption, temperature, logger_error, force_mavlink1=False): ''' High Rate Telemetry @@ -3937,6 +4021,7 @@ class MAVLink(object): dpl_state : Deployment Controller State (type:uint8_t) abk_state : Airbrake FSM state (type:uint8_t) nas_state : Navigation System FSM State (type:uint8_t) + mea_state : MEA Controller State (type:uint8_t) pressure_ada : Atmospheric pressure estimated by ADA [Pa] (type:float) pressure_digi : Pressure from digital sensor [Pa] (type:float) pressure_static : Pressure from static port [Pa] (type:float) @@ -3944,6 +4029,7 @@ class MAVLink(object): airspeed_pitot : Pitot airspeed [m/s] (type:float) altitude_agl : Altitude above ground level [m] (type:float) ada_vert_speed : Vertical speed estimated by ADA [m/s] (type:float) + mea_mass : Mass estimated by MEA [kg] (type:float) acc_x : Acceleration on X axis (body) [m/s^2] (type:float) acc_y : Acceleration on Y axis (body) [m/s^2] (type:float) acc_z : Acceleration on Z axis (body) [m/s^2] (type:float) @@ -3958,8 +4044,6 @@ class MAVLink(object): gps_lon : Longitude [deg] (type:float) gps_alt : GPS Altitude [m] (type:float) abk_angle : Air Brakes angle [deg] (type:float) - abk_estimated_cd : Estimated drag coefficient (type:float) - parachute_load : Parachute load cell value (type:float) 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) @@ -3977,15 +4061,15 @@ class MAVLink(object): 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) - estimated_thrust : Estimated thrust from automatic shutdown algorithm (type:float) - vbat : Battery voltage [V] (type:float) + battery_voltage : Battery voltage [V] (type:float) + current_consumption : Battery current [A] (type:float) temperature : Temperature [degC] (type:float) logger_error : Logger error (0 = no error, -1 otherwise) (type:int8_t) ''' - return self.send(self.rocket_flight_tm_encode(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, abk_estimated_cd, parachute_load, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, estimated_thrust, vbat, temperature, logger_error), force_mavlink1=force_mavlink1) + return self.send(self.rocket_flight_tm_encode(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, current_consumption, temperature, logger_error), force_mavlink1=force_mavlink1) - def payload_flight_tm_encode(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, vbat, vsupply_5v, temperature, logger_error): + def payload_flight_tm_encode(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, current_consumption, vsupply_5v, temperature, logger_error): ''' High Rate Telemetry @@ -4028,15 +4112,16 @@ class MAVLink(object): wes_n : Wind estimated north velocity [m/s] (type:float) wes_e : Wind estimated east velocity [m/s] (type:float) pin_nosecone : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t) - vbat : Battery voltage [V] (type:float) + battery_voltage : Battery voltage [V] (type:float) + current_consumption : Battery current [A] (type:float) vsupply_5v : Power supply 5V [V] (type:float) temperature : Temperature [degC] (type:float) logger_error : Logger error (0 = no error) (type:int8_t) ''' - return MAVLink_payload_flight_tm_message(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, vbat, vsupply_5v, temperature, logger_error) + return MAVLink_payload_flight_tm_message(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, current_consumption, vsupply_5v, temperature, logger_error) - def payload_flight_tm_send(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, vbat, vsupply_5v, temperature, logger_error, force_mavlink1=False): + def payload_flight_tm_send(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, current_consumption, vsupply_5v, temperature, logger_error, force_mavlink1=False): ''' High Rate Telemetry @@ -4079,13 +4164,14 @@ class MAVLink(object): wes_n : Wind estimated north velocity [m/s] (type:float) wes_e : Wind estimated east velocity [m/s] (type:float) pin_nosecone : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t) - vbat : Battery voltage [V] (type:float) + battery_voltage : Battery voltage [V] (type:float) + current_consumption : Battery current [A] (type:float) vsupply_5v : Power supply 5V [V] (type:float) temperature : Temperature [degC] (type:float) logger_error : Logger error (0 = no error) (type:int8_t) ''' - return self.send(self.payload_flight_tm_encode(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, vbat, vsupply_5v, temperature, logger_error), force_mavlink1=force_mavlink1) + return self.send(self.payload_flight_tm_encode(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, current_consumption, vsupply_5v, temperature, logger_error), force_mavlink1=force_mavlink1) def rocket_stats_tm_encode(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_vane_max_pressure, cpu_load, free_heap): ''' @@ -4235,7 +4321,7 @@ class MAVLink(object): ''' return self.send(self.gse_tm_encode(timestamp, loadcell_tank, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status), force_mavlink1=force_mavlink1) - def motor_tm_encode(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state): + def motor_tm_encode(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, battery_voltage, current_consumption): ''' Motor rocket telemetry @@ -4246,11 +4332,13 @@ class MAVLink(object): floating_level : Floating level in tank (type:uint8_t) tank_temperature : Tank temperature (type:float) main_valve_state : 1 If the main valve is open (type:uint8_t) + battery_voltage : Battery voltage [V] (type:float) + current_consumption : Current drained from the battery [A] (type:float) ''' - return MAVLink_motor_tm_message(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state) + return MAVLink_motor_tm_message(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, battery_voltage, current_consumption) - def motor_tm_send(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, force_mavlink1=False): + def motor_tm_send(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, battery_voltage, current_consumption, force_mavlink1=False): ''' Motor rocket telemetry @@ -4261,7 +4349,9 @@ class MAVLink(object): floating_level : Floating level in tank (type:uint8_t) tank_temperature : Tank temperature (type:float) main_valve_state : 1 If the main valve is open (type:uint8_t) + battery_voltage : Battery voltage [V] (type:float) + current_consumption : Current drained from the battery [A] (type:float) ''' - return self.send(self.motor_tm_encode(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state), force_mavlink1=force_mavlink1) + return self.send(self.motor_tm_encode(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, battery_voltage, current_consumption), force_mavlink1=force_mavlink1) diff --git a/mavlink_lib/gemini/gemini.h b/mavlink_lib/gemini/gemini.h index 74c55f0..fef3116 100644 --- a/mavlink_lib/gemini/gemini.h +++ b/mavlink_lib/gemini/gemini.h @@ -11,7 +11,7 @@ #endif #undef MAVLINK_THIS_XML_HASH -#define MAVLINK_THIS_XML_HASH -129419792422964465 +#define MAVLINK_THIS_XML_HASH -2036237758109455771 #ifdef __cplusplus extern "C" { @@ -20,11 +20,11 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 44, 32, 32, 32, 32, 56, 21, 5, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 46, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 46, 28, 27, 53, 77, 0, 171, 158, 92, 76, 42, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 44, 32, 32, 32, 32, 56, 21, 5, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 46, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 46, 28, 27, 53, 77, 29, 168, 162, 92, 76, 42, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 57, 72, 87, 223, 245, 212, 140, 148, 6, 155, 87, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 104, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 242, 142, 108, 133, 234, 66, 0, 141, 229, 245, 115, 89, 241, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 57, 72, 87, 223, 245, 212, 140, 148, 6, 155, 87, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 104, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 242, 142, 108, 133, 234, 66, 11, 254, 117, 245, 115, 89, 196, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #endif #include "../protocol.h" @@ -34,6 +34,18 @@ extern "C" { // ENUM DEFINITIONS +/** @brief Enum that lists all the system IDs of the various devices */ +#ifndef HAVE_ENUM_SysIDs +#define HAVE_ENUM_SysIDs +typedef enum SysIDs +{ + MAIN=1, /* | */ + PAYLOAD=2, /* | */ + RIG=3, /* | */ + SysIDs_ENUM_END=4, /* | */ +} SysIDs; +#endif + /** @brief Enum list for all the telemetries that can be requested */ #ifndef HAVE_ENUM_SystemTMList #define HAVE_ENUM_SystemTMList @@ -47,13 +59,13 @@ typedef enum SystemTMList MAV_TASK_STATS_ID=6, /* Task scheduler statistics answer: n mavlink messages where n is the number of tasks | */ MAV_ADA_ID=7, /* ADA Status | */ MAV_NAS_ID=8, /* NavigationSystem data | */ - MAV_CAN_ID=9, /* Canbus stats | */ - MAV_FLIGHT_ID=10, /* Flight telemetry | */ - MAV_STATS_ID=11, /* Satistics telemetry | */ - MAV_SENSORS_STATE_ID=12, /* Sensors init state telemetry | */ - MAV_GSE_ID=13, /* Ground Segnement Equipment | */ - MAV_MOTOR_ID=14, /* Rocket Motor data | */ - MAV_TARS_ID=15, /* TARS data | */ + MAV_MEA_ID=9, /* MEA Status | */ + MAV_CAN_ID=10, /* Canbus stats | */ + MAV_FLIGHT_ID=11, /* Flight telemetry | */ + MAV_STATS_ID=12, /* Satistics telemetry | */ + MAV_SENSORS_STATE_ID=13, /* Sensors init state telemetry | */ + MAV_GSE_ID=14, /* Ground Segnement Equipment | */ + MAV_MOTOR_ID=15, /* Rocket Motor data | */ SystemTMList_ENUM_END=16, /* | */ } SystemTMList; #endif @@ -205,6 +217,7 @@ typedef enum PinsList #include "./mavlink_msg_task_stats_tm.h" #include "./mavlink_msg_ada_tm.h" #include "./mavlink_msg_nas_tm.h" +#include "./mavlink_msg_mea_tm.h" #include "./mavlink_msg_rocket_flight_tm.h" #include "./mavlink_msg_payload_flight_tm.h" #include "./mavlink_msg_rocket_stats_tm.h" @@ -216,11 +229,11 @@ typedef enum PinsList #undef MAVLINK_THIS_XML_HASH -#define MAVLINK_THIS_XML_HASH -129419792422964465 +#define MAVLINK_THIS_XML_HASH -2036237758109455771 #if MAVLINK_THIS_XML_HASH == MAVLINK_PRIMARY_XML_HASH -# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_RECEIVER_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_FSM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} -# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 105 }, { "ATTITUDE_TM", 110 }, { "COMMAND_TC", 2 }, { "CONRIG_STATE_TC", 19 }, { "CURRENT_TM", 107 }, { "FSM_TM", 201 }, { "GPS_TM", 102 }, { "GSE_TM", 212 }, { "IMU_TM", 103 }, { "LOAD_TM", 109 }, { "LOGGER_TM", 202 }, { "MAVLINK_STATS_TM", 203 }, { "MOTOR_TM", 213 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 113 }, { "PRESSURE_TM", 104 }, { "RAW_EVENT_TC", 13 }, { "RECEIVER_TM", 150 }, { "RESET_SERVO_TC", 8 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 111 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 112 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 16 }, { "SET_ATOMIC_VALVE_TIMING_TC", 17 }, { "SET_COORDINATES_TC", 12 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 14 }, { "SET_IGNITION_TIME_TC", 20 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_TARGET_COORDINATES_TC", 15 }, { "SET_VALVE_MAXIMUM_APERTURE_TC", 18 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 108 }, { "VOLTAGE_TM", 106 }, { "WIGGLE_SERVO_TC", 7 }} +# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_RECEIVER_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_FSM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_MEA_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 105 }, { "ATTITUDE_TM", 110 }, { "COMMAND_TC", 2 }, { "CONRIG_STATE_TC", 19 }, { "CURRENT_TM", 107 }, { "FSM_TM", 201 }, { "GPS_TM", 102 }, { "GSE_TM", 212 }, { "IMU_TM", 103 }, { "LOAD_TM", 109 }, { "LOGGER_TM", 202 }, { "MAVLINK_STATS_TM", 203 }, { "MEA_TM", 207 }, { "MOTOR_TM", 213 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 113 }, { "PRESSURE_TM", 104 }, { "RAW_EVENT_TC", 13 }, { "RECEIVER_TM", 150 }, { "RESET_SERVO_TC", 8 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 111 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 112 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 16 }, { "SET_ATOMIC_VALVE_TIMING_TC", 17 }, { "SET_COORDINATES_TC", 12 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 14 }, { "SET_IGNITION_TIME_TC", 20 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_TARGET_COORDINATES_TC", 15 }, { "SET_VALVE_MAXIMUM_APERTURE_TC", 18 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 108 }, { "VOLTAGE_TM", 106 }, { "WIGGLE_SERVO_TC", 7 }} # if MAVLINK_COMMAND_24BIT # include "../mavlink_get_info.h" # endif diff --git a/mavlink_lib/gemini/mavlink.h b/mavlink_lib/gemini/mavlink.h index 328a3cc..29670ce 100644 --- a/mavlink_lib/gemini/mavlink.h +++ b/mavlink_lib/gemini/mavlink.h @@ -6,7 +6,7 @@ #ifndef MAVLINK_H #define MAVLINK_H -#define MAVLINK_PRIMARY_XML_HASH -129419792422964465 +#define MAVLINK_PRIMARY_XML_HASH -2036237758109455771 #ifndef MAVLINK_STX #define MAVLINK_STX 254 diff --git a/mavlink_lib/gemini/mavlink_msg_mea_tm.h b/mavlink_lib/gemini/mavlink_msg_mea_tm.h new file mode 100644 index 0000000..a3887d7 --- /dev/null +++ b/mavlink_lib/gemini/mavlink_msg_mea_tm.h @@ -0,0 +1,363 @@ +#pragma once +// MESSAGE MEA_TM PACKING + +#define MAVLINK_MSG_ID_MEA_TM 207 + + +typedef struct __mavlink_mea_tm_t { + uint64_t timestamp; /*< [us] When was this logged*/ + float kalman_x0; /*< Kalman state variable 0 (corrected pressure)*/ + float kalman_x1; /*< Kalman state variable 1 */ + float kalman_x2; /*< Kalman state variable 2 (mass)*/ + float mass; /*< [kg] Mass estimated*/ + float corrected_pressure; /*< [kg] Corrected pressure*/ + uint8_t state; /*< MEA current state*/ +} mavlink_mea_tm_t; + +#define MAVLINK_MSG_ID_MEA_TM_LEN 29 +#define MAVLINK_MSG_ID_MEA_TM_MIN_LEN 29 +#define MAVLINK_MSG_ID_207_LEN 29 +#define MAVLINK_MSG_ID_207_MIN_LEN 29 + +#define MAVLINK_MSG_ID_MEA_TM_CRC 11 +#define MAVLINK_MSG_ID_207_CRC 11 + + + +#if MAVLINK_COMMAND_24BIT +#define MAVLINK_MESSAGE_INFO_MEA_TM { \ + 207, \ + "MEA_TM", \ + 7, \ + { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mea_tm_t, timestamp) }, \ + { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_mea_tm_t, state) }, \ + { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mea_tm_t, kalman_x0) }, \ + { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mea_tm_t, kalman_x1) }, \ + { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mea_tm_t, kalman_x2) }, \ + { "mass", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mea_tm_t, mass) }, \ + { "corrected_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mea_tm_t, corrected_pressure) }, \ + } \ +} +#else +#define MAVLINK_MESSAGE_INFO_MEA_TM { \ + "MEA_TM", \ + 7, \ + { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mea_tm_t, timestamp) }, \ + { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_mea_tm_t, state) }, \ + { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mea_tm_t, kalman_x0) }, \ + { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mea_tm_t, kalman_x1) }, \ + { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mea_tm_t, kalman_x2) }, \ + { "mass", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mea_tm_t, mass) }, \ + { "corrected_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mea_tm_t, corrected_pressure) }, \ + } \ +} +#endif + +/** + * @brief Pack a mea_tm message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param timestamp [us] When was this logged + * @param state MEA current state + * @param kalman_x0 Kalman state variable 0 (corrected pressure) + * @param kalman_x1 Kalman state variable 1 + * @param kalman_x2 Kalman state variable 2 (mass) + * @param mass [kg] Mass estimated + * @param corrected_pressure [kg] Corrected pressure + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mea_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MEA_TM_LEN]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_float(buf, 8, kalman_x0); + _mav_put_float(buf, 12, kalman_x1); + _mav_put_float(buf, 16, kalman_x2); + _mav_put_float(buf, 20, mass); + _mav_put_float(buf, 24, corrected_pressure); + _mav_put_uint8_t(buf, 28, state); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEA_TM_LEN); +#else + mavlink_mea_tm_t packet; + packet.timestamp = timestamp; + packet.kalman_x0 = kalman_x0; + packet.kalman_x1 = kalman_x1; + packet.kalman_x2 = kalman_x2; + packet.mass = mass; + packet.corrected_pressure = corrected_pressure; + packet.state = state; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEA_TM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEA_TM; + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC); +} + +/** + * @brief Pack a mea_tm message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param timestamp [us] When was this logged + * @param state MEA current state + * @param kalman_x0 Kalman state variable 0 (corrected pressure) + * @param kalman_x1 Kalman state variable 1 + * @param kalman_x2 Kalman state variable 2 (mass) + * @param mass [kg] Mass estimated + * @param corrected_pressure [kg] Corrected pressure + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mea_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t timestamp,uint8_t state,float kalman_x0,float kalman_x1,float kalman_x2,float mass,float corrected_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MEA_TM_LEN]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_float(buf, 8, kalman_x0); + _mav_put_float(buf, 12, kalman_x1); + _mav_put_float(buf, 16, kalman_x2); + _mav_put_float(buf, 20, mass); + _mav_put_float(buf, 24, corrected_pressure); + _mav_put_uint8_t(buf, 28, state); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEA_TM_LEN); +#else + mavlink_mea_tm_t packet; + packet.timestamp = timestamp; + packet.kalman_x0 = kalman_x0; + packet.kalman_x1 = kalman_x1; + packet.kalman_x2 = kalman_x2; + packet.mass = mass; + packet.corrected_pressure = corrected_pressure; + packet.state = state; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEA_TM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEA_TM; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC); +} + +/** + * @brief Encode a mea_tm struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mea_tm C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mea_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mea_tm_t* mea_tm) +{ + return mavlink_msg_mea_tm_pack(system_id, component_id, msg, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure); +} + +/** + * @brief Encode a mea_tm struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mea_tm C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mea_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mea_tm_t* mea_tm) +{ + return mavlink_msg_mea_tm_pack_chan(system_id, component_id, chan, msg, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure); +} + +/** + * @brief Send a mea_tm message + * @param chan MAVLink channel to send the message + * + * @param timestamp [us] When was this logged + * @param state MEA current state + * @param kalman_x0 Kalman state variable 0 (corrected pressure) + * @param kalman_x1 Kalman state variable 1 + * @param kalman_x2 Kalman state variable 2 (mass) + * @param mass [kg] Mass estimated + * @param corrected_pressure [kg] Corrected pressure + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mea_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MEA_TM_LEN]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_float(buf, 8, kalman_x0); + _mav_put_float(buf, 12, kalman_x1); + _mav_put_float(buf, 16, kalman_x2); + _mav_put_float(buf, 20, mass); + _mav_put_float(buf, 24, corrected_pressure); + _mav_put_uint8_t(buf, 28, state); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, buf, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC); +#else + mavlink_mea_tm_t packet; + packet.timestamp = timestamp; + packet.kalman_x0 = kalman_x0; + packet.kalman_x1 = kalman_x1; + packet.kalman_x2 = kalman_x2; + packet.mass = mass; + packet.corrected_pressure = corrected_pressure; + packet.state = state; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, (const char *)&packet, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC); +#endif +} + +/** + * @brief Send a mea_tm message + * @param chan MAVLink channel to send the message + * @param struct The MAVLink struct to serialize + */ +static inline void mavlink_msg_mea_tm_send_struct(mavlink_channel_t chan, const mavlink_mea_tm_t* mea_tm) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + mavlink_msg_mea_tm_send(chan, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, (const char *)mea_tm, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC); +#endif +} + +#if MAVLINK_MSG_ID_MEA_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This variant of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mea_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_float(buf, 8, kalman_x0); + _mav_put_float(buf, 12, kalman_x1); + _mav_put_float(buf, 16, kalman_x2); + _mav_put_float(buf, 20, mass); + _mav_put_float(buf, 24, corrected_pressure); + _mav_put_uint8_t(buf, 28, state); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, buf, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC); +#else + mavlink_mea_tm_t *packet = (mavlink_mea_tm_t *)msgbuf; + packet->timestamp = timestamp; + packet->kalman_x0 = kalman_x0; + packet->kalman_x1 = kalman_x1; + packet->kalman_x2 = kalman_x2; + packet->mass = mass; + packet->corrected_pressure = corrected_pressure; + packet->state = state; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, (const char *)packet, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC); +#endif +} +#endif + +#endif + +// MESSAGE MEA_TM UNPACKING + + +/** + * @brief Get field timestamp from mea_tm message + * + * @return [us] When was this logged + */ +static inline uint64_t mavlink_msg_mea_tm_get_timestamp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field state from mea_tm message + * + * @return MEA current state + */ +static inline uint8_t mavlink_msg_mea_tm_get_state(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 28); +} + +/** + * @brief Get field kalman_x0 from mea_tm message + * + * @return Kalman state variable 0 (corrected pressure) + */ +static inline float mavlink_msg_mea_tm_get_kalman_x0(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field kalman_x1 from mea_tm message + * + * @return Kalman state variable 1 + */ +static inline float mavlink_msg_mea_tm_get_kalman_x1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field kalman_x2 from mea_tm message + * + * @return Kalman state variable 2 (mass) + */ +static inline float mavlink_msg_mea_tm_get_kalman_x2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field mass from mea_tm message + * + * @return [kg] Mass estimated + */ +static inline float mavlink_msg_mea_tm_get_mass(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field corrected_pressure from mea_tm message + * + * @return [kg] Corrected pressure + */ +static inline float mavlink_msg_mea_tm_get_corrected_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a mea_tm message into a struct + * + * @param msg The message to decode + * @param mea_tm C-struct to decode the message contents into + */ +static inline void mavlink_msg_mea_tm_decode(const mavlink_message_t* msg, mavlink_mea_tm_t* mea_tm) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + mea_tm->timestamp = mavlink_msg_mea_tm_get_timestamp(msg); + mea_tm->kalman_x0 = mavlink_msg_mea_tm_get_kalman_x0(msg); + mea_tm->kalman_x1 = mavlink_msg_mea_tm_get_kalman_x1(msg); + mea_tm->kalman_x2 = mavlink_msg_mea_tm_get_kalman_x2(msg); + mea_tm->mass = mavlink_msg_mea_tm_get_mass(msg); + mea_tm->corrected_pressure = mavlink_msg_mea_tm_get_corrected_pressure(msg); + mea_tm->state = mavlink_msg_mea_tm_get_state(msg); +#else + uint8_t len = msg->len < MAVLINK_MSG_ID_MEA_TM_LEN? msg->len : MAVLINK_MSG_ID_MEA_TM_LEN; + memset(mea_tm, 0, MAVLINK_MSG_ID_MEA_TM_LEN); + memcpy(mea_tm, _MAV_PAYLOAD(msg), len); +#endif +} diff --git a/mavlink_lib/gemini/mavlink_msg_motor_tm.h b/mavlink_lib/gemini/mavlink_msg_motor_tm.h index 508ce65..969ea55 100644 --- a/mavlink_lib/gemini/mavlink_msg_motor_tm.h +++ b/mavlink_lib/gemini/mavlink_msg_motor_tm.h @@ -10,17 +10,19 @@ typedef struct __mavlink_motor_tm_t { float bottom_tank_pressure; /*< [Bar] Tank bottom pressure*/ float combustion_chamber_pressure; /*< [Bar] Pressure inside the combustion chamber used for automatic shutdown*/ float tank_temperature; /*< Tank temperature*/ + float battery_voltage; /*< [V] Battery voltage*/ + float current_consumption; /*< [A] Current drained from the battery*/ uint8_t floating_level; /*< Floating level in tank*/ - uint8_t main_valve_state; /*< 1 If the main valve is open */ + uint8_t main_valve_state; /*< 1 If the main valve is open */ } mavlink_motor_tm_t; -#define MAVLINK_MSG_ID_MOTOR_TM_LEN 26 -#define MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN 26 -#define MAVLINK_MSG_ID_213_LEN 26 -#define MAVLINK_MSG_ID_213_MIN_LEN 26 +#define MAVLINK_MSG_ID_MOTOR_TM_LEN 34 +#define MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN 34 +#define MAVLINK_MSG_ID_213_LEN 34 +#define MAVLINK_MSG_ID_213_MIN_LEN 34 -#define MAVLINK_MSG_ID_MOTOR_TM_CRC 241 -#define MAVLINK_MSG_ID_213_CRC 241 +#define MAVLINK_MSG_ID_MOTOR_TM_CRC 196 +#define MAVLINK_MSG_ID_213_CRC 196 @@ -28,27 +30,31 @@ typedef struct __mavlink_motor_tm_t { #define MAVLINK_MESSAGE_INFO_MOTOR_TM { \ 213, \ "MOTOR_TM", \ - 7, \ + 9, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_motor_tm_t, timestamp) }, \ { "top_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_motor_tm_t, top_tank_pressure) }, \ { "bottom_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_motor_tm_t, bottom_tank_pressure) }, \ { "combustion_chamber_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_motor_tm_t, combustion_chamber_pressure) }, \ - { "floating_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_motor_tm_t, floating_level) }, \ + { "floating_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_motor_tm_t, floating_level) }, \ { "tank_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_motor_tm_t, tank_temperature) }, \ - { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_motor_tm_t, main_valve_state) }, \ + { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_motor_tm_t, main_valve_state) }, \ + { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_motor_tm_t, battery_voltage) }, \ + { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_motor_tm_t, current_consumption) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_MOTOR_TM { \ "MOTOR_TM", \ - 7, \ + 9, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_motor_tm_t, timestamp) }, \ { "top_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_motor_tm_t, top_tank_pressure) }, \ { "bottom_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_motor_tm_t, bottom_tank_pressure) }, \ { "combustion_chamber_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_motor_tm_t, combustion_chamber_pressure) }, \ - { "floating_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_motor_tm_t, floating_level) }, \ + { "floating_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_motor_tm_t, floating_level) }, \ { "tank_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_motor_tm_t, tank_temperature) }, \ - { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_motor_tm_t, main_valve_state) }, \ + { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_motor_tm_t, main_valve_state) }, \ + { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_motor_tm_t, battery_voltage) }, \ + { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_motor_tm_t, current_consumption) }, \ } \ } #endif @@ -65,11 +71,13 @@ typedef struct __mavlink_motor_tm_t { * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown * @param floating_level Floating level in tank * @param tank_temperature Tank temperature - * @param main_valve_state 1 If the main valve is open + * @param main_valve_state 1 If the main valve is open + * @param battery_voltage [V] Battery voltage + * @param current_consumption [A] Current drained from the battery * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state) + uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, float battery_voltage, float current_consumption) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN]; @@ -78,8 +86,10 @@ static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t comp _mav_put_float(buf, 12, bottom_tank_pressure); _mav_put_float(buf, 16, combustion_chamber_pressure); _mav_put_float(buf, 20, tank_temperature); - _mav_put_uint8_t(buf, 24, floating_level); - _mav_put_uint8_t(buf, 25, main_valve_state); + _mav_put_float(buf, 24, battery_voltage); + _mav_put_float(buf, 28, current_consumption); + _mav_put_uint8_t(buf, 32, floating_level); + _mav_put_uint8_t(buf, 33, main_valve_state); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOTOR_TM_LEN); #else @@ -89,6 +99,8 @@ static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t comp packet.bottom_tank_pressure = bottom_tank_pressure; packet.combustion_chamber_pressure = combustion_chamber_pressure; packet.tank_temperature = tank_temperature; + packet.battery_voltage = battery_voltage; + packet.current_consumption = current_consumption; packet.floating_level = floating_level; packet.main_valve_state = main_valve_state; @@ -111,12 +123,14 @@ static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t comp * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown * @param floating_level Floating level in tank * @param tank_temperature Tank temperature - * @param main_valve_state 1 If the main valve is open + * @param main_valve_state 1 If the main valve is open + * @param battery_voltage [V] Battery voltage + * @param current_consumption [A] Current drained from the battery * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - uint64_t timestamp,float top_tank_pressure,float bottom_tank_pressure,float combustion_chamber_pressure,uint8_t floating_level,float tank_temperature,uint8_t main_valve_state) + uint64_t timestamp,float top_tank_pressure,float bottom_tank_pressure,float combustion_chamber_pressure,uint8_t floating_level,float tank_temperature,uint8_t main_valve_state,float battery_voltage,float current_consumption) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN]; @@ -125,8 +139,10 @@ static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t _mav_put_float(buf, 12, bottom_tank_pressure); _mav_put_float(buf, 16, combustion_chamber_pressure); _mav_put_float(buf, 20, tank_temperature); - _mav_put_uint8_t(buf, 24, floating_level); - _mav_put_uint8_t(buf, 25, main_valve_state); + _mav_put_float(buf, 24, battery_voltage); + _mav_put_float(buf, 28, current_consumption); + _mav_put_uint8_t(buf, 32, floating_level); + _mav_put_uint8_t(buf, 33, main_valve_state); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOTOR_TM_LEN); #else @@ -136,6 +152,8 @@ static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t packet.bottom_tank_pressure = bottom_tank_pressure; packet.combustion_chamber_pressure = combustion_chamber_pressure; packet.tank_temperature = tank_temperature; + packet.battery_voltage = battery_voltage; + packet.current_consumption = current_consumption; packet.floating_level = floating_level; packet.main_valve_state = main_valve_state; @@ -156,7 +174,7 @@ static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t */ static inline uint16_t mavlink_msg_motor_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_motor_tm_t* motor_tm) { - return mavlink_msg_motor_tm_pack(system_id, component_id, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state); + return mavlink_msg_motor_tm_pack(system_id, component_id, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->battery_voltage, motor_tm->current_consumption); } /** @@ -170,7 +188,7 @@ static inline uint16_t mavlink_msg_motor_tm_encode(uint8_t system_id, uint8_t co */ static inline uint16_t mavlink_msg_motor_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_motor_tm_t* motor_tm) { - return mavlink_msg_motor_tm_pack_chan(system_id, component_id, chan, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state); + return mavlink_msg_motor_tm_pack_chan(system_id, component_id, chan, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->battery_voltage, motor_tm->current_consumption); } /** @@ -183,11 +201,13 @@ static inline uint16_t mavlink_msg_motor_tm_encode_chan(uint8_t system_id, uint8 * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown * @param floating_level Floating level in tank * @param tank_temperature Tank temperature - * @param main_valve_state 1 If the main valve is open + * @param main_valve_state 1 If the main valve is open + * @param battery_voltage [V] Battery voltage + * @param current_consumption [A] Current drained from the battery */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state) +static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, float battery_voltage, float current_consumption) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN]; @@ -196,8 +216,10 @@ static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t ti _mav_put_float(buf, 12, bottom_tank_pressure); _mav_put_float(buf, 16, combustion_chamber_pressure); _mav_put_float(buf, 20, tank_temperature); - _mav_put_uint8_t(buf, 24, floating_level); - _mav_put_uint8_t(buf, 25, main_valve_state); + _mav_put_float(buf, 24, battery_voltage); + _mav_put_float(buf, 28, current_consumption); + _mav_put_uint8_t(buf, 32, floating_level); + _mav_put_uint8_t(buf, 33, main_valve_state); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, buf, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC); #else @@ -207,6 +229,8 @@ static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t ti packet.bottom_tank_pressure = bottom_tank_pressure; packet.combustion_chamber_pressure = combustion_chamber_pressure; packet.tank_temperature = tank_temperature; + packet.battery_voltage = battery_voltage; + packet.current_consumption = current_consumption; packet.floating_level = floating_level; packet.main_valve_state = main_valve_state; @@ -222,7 +246,7 @@ static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t ti static inline void mavlink_msg_motor_tm_send_struct(mavlink_channel_t chan, const mavlink_motor_tm_t* motor_tm) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_motor_tm_send(chan, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state); + mavlink_msg_motor_tm_send(chan, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->battery_voltage, motor_tm->current_consumption); #else _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, (const char *)motor_tm, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC); #endif @@ -236,7 +260,7 @@ static inline void mavlink_msg_motor_tm_send_struct(mavlink_channel_t chan, cons is usually the receive buffer for the channel, and allows a reply to an incoming message with minimum stack space usage. */ -static inline void mavlink_msg_motor_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state) +static inline void mavlink_msg_motor_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, float battery_voltage, float current_consumption) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char *buf = (char *)msgbuf; @@ -245,8 +269,10 @@ static inline void mavlink_msg_motor_tm_send_buf(mavlink_message_t *msgbuf, mavl _mav_put_float(buf, 12, bottom_tank_pressure); _mav_put_float(buf, 16, combustion_chamber_pressure); _mav_put_float(buf, 20, tank_temperature); - _mav_put_uint8_t(buf, 24, floating_level); - _mav_put_uint8_t(buf, 25, main_valve_state); + _mav_put_float(buf, 24, battery_voltage); + _mav_put_float(buf, 28, current_consumption); + _mav_put_uint8_t(buf, 32, floating_level); + _mav_put_uint8_t(buf, 33, main_valve_state); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, buf, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC); #else @@ -256,6 +282,8 @@ static inline void mavlink_msg_motor_tm_send_buf(mavlink_message_t *msgbuf, mavl packet->bottom_tank_pressure = bottom_tank_pressure; packet->combustion_chamber_pressure = combustion_chamber_pressure; packet->tank_temperature = tank_temperature; + packet->battery_voltage = battery_voltage; + packet->current_consumption = current_consumption; packet->floating_level = floating_level; packet->main_valve_state = main_valve_state; @@ -316,7 +344,7 @@ static inline float mavlink_msg_motor_tm_get_combustion_chamber_pressure(const m */ static inline uint8_t mavlink_msg_motor_tm_get_floating_level(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 24); + return _MAV_RETURN_uint8_t(msg, 32); } /** @@ -332,11 +360,31 @@ static inline float mavlink_msg_motor_tm_get_tank_temperature(const mavlink_mess /** * @brief Get field main_valve_state from motor_tm message * - * @return 1 If the main valve is open + * @return 1 If the main valve is open */ static inline uint8_t mavlink_msg_motor_tm_get_main_valve_state(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 25); + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field battery_voltage from motor_tm message + * + * @return [V] Battery voltage + */ +static inline float mavlink_msg_motor_tm_get_battery_voltage(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field current_consumption from motor_tm message + * + * @return [A] Current drained from the battery + */ +static inline float mavlink_msg_motor_tm_get_current_consumption(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); } /** @@ -353,6 +401,8 @@ static inline void mavlink_msg_motor_tm_decode(const mavlink_message_t* msg, mav motor_tm->bottom_tank_pressure = mavlink_msg_motor_tm_get_bottom_tank_pressure(msg); motor_tm->combustion_chamber_pressure = mavlink_msg_motor_tm_get_combustion_chamber_pressure(msg); motor_tm->tank_temperature = mavlink_msg_motor_tm_get_tank_temperature(msg); + motor_tm->battery_voltage = mavlink_msg_motor_tm_get_battery_voltage(msg); + motor_tm->current_consumption = mavlink_msg_motor_tm_get_current_consumption(msg); motor_tm->floating_level = mavlink_msg_motor_tm_get_floating_level(msg); motor_tm->main_valve_state = mavlink_msg_motor_tm_get_main_valve_state(msg); #else diff --git a/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h b/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h index f68e041..ae98a6d 100644 --- a/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h +++ b/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h @@ -39,7 +39,8 @@ typedef struct __mavlink_payload_flight_tm_t { float nas_bias_z; /*< Navigation system gyroscope bias on z axis*/ float wes_n; /*< [m/s] Wind estimated north velocity*/ float wes_e; /*< [m/s] Wind estimated east velocity*/ - float vbat; /*< [V] Battery voltage*/ + float battery_voltage; /*< [V] Battery voltage*/ + float current_consumption; /*< [A] Battery current*/ float vsupply_5v; /*< [V] Power supply 5V*/ float temperature; /*< [degC] Temperature*/ uint8_t fmm_state; /*< Flight Mode Manager State*/ @@ -50,13 +51,13 @@ typedef struct __mavlink_payload_flight_tm_t { int8_t logger_error; /*< Logger error (0 = no error)*/ } mavlink_payload_flight_tm_t; -#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN 158 -#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN 158 -#define MAVLINK_MSG_ID_209_LEN 158 -#define MAVLINK_MSG_ID_209_MIN_LEN 158 +#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN 162 +#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN 162 +#define MAVLINK_MSG_ID_209_LEN 162 +#define MAVLINK_MSG_ID_209_MIN_LEN 162 -#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC 229 -#define MAVLINK_MSG_ID_209_CRC 229 +#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC 117 +#define MAVLINK_MSG_ID_209_CRC 117 @@ -64,11 +65,11 @@ typedef struct __mavlink_payload_flight_tm_t { #define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \ 209, \ "PAYLOAD_FLIGHT_TM", \ - 43, \ + 44, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \ - { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 152, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \ - { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 153, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \ - { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 154, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \ + { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \ + { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \ + { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \ { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \ { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \ { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \ @@ -82,7 +83,7 @@ typedef struct __mavlink_payload_flight_tm_t { { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_flight_tm_t, mag_x) }, \ { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_flight_tm_t, mag_y) }, \ { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_flight_tm_t, mag_z) }, \ - { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 155, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \ + { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \ { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \ { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \ { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \ @@ -103,21 +104,22 @@ typedef struct __mavlink_payload_flight_tm_t { { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_flight_tm_t, nas_bias_z) }, \ { "wes_n", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_flight_tm_t, wes_n) }, \ { "wes_e", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_payload_flight_tm_t, wes_e) }, \ - { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \ - { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, vbat) }, \ - { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, vsupply_5v) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, temperature) }, \ - { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \ + { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \ + { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, battery_voltage) }, \ + { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, current_consumption) }, \ + { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, vsupply_5v) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \ + { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \ "PAYLOAD_FLIGHT_TM", \ - 43, \ + 44, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \ - { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 152, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \ - { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 153, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \ - { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 154, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \ + { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \ + { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \ + { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \ { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \ { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \ { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \ @@ -131,7 +133,7 @@ typedef struct __mavlink_payload_flight_tm_t { { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_flight_tm_t, mag_x) }, \ { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_flight_tm_t, mag_y) }, \ { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_flight_tm_t, mag_z) }, \ - { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 155, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \ + { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \ { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \ { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \ { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \ @@ -152,11 +154,12 @@ typedef struct __mavlink_payload_flight_tm_t { { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_flight_tm_t, nas_bias_z) }, \ { "wes_n", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_flight_tm_t, wes_n) }, \ { "wes_e", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_payload_flight_tm_t, wes_e) }, \ - { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \ - { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, vbat) }, \ - { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, vsupply_5v) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, temperature) }, \ - { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \ + { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \ + { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, battery_voltage) }, \ + { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, current_consumption) }, \ + { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, vsupply_5v) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \ + { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \ } \ } #endif @@ -206,14 +209,15 @@ typedef struct __mavlink_payload_flight_tm_t { * @param wes_n [m/s] Wind estimated north velocity * @param wes_e [m/s] Wind estimated east velocity * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected) - * @param vbat [V] Battery voltage + * @param battery_voltage [V] Battery voltage + * @param current_consumption [A] Battery current * @param vsupply_5v [V] Power supply 5V * @param temperature [degC] Temperature * @param logger_error Logger error (0 = no error) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float vbat, float vsupply_5v, float temperature, int8_t logger_error) + uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float current_consumption, float vsupply_5v, float temperature, int8_t logger_error) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN]; @@ -251,15 +255,16 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin _mav_put_float(buf, 128, nas_bias_z); _mav_put_float(buf, 132, wes_n); _mav_put_float(buf, 136, wes_e); - _mav_put_float(buf, 140, vbat); - _mav_put_float(buf, 144, vsupply_5v); - _mav_put_float(buf, 148, temperature); - _mav_put_uint8_t(buf, 152, fmm_state); - _mav_put_uint8_t(buf, 153, nas_state); - _mav_put_uint8_t(buf, 154, wes_state); - _mav_put_uint8_t(buf, 155, gps_fix); - _mav_put_uint8_t(buf, 156, pin_nosecone); - _mav_put_int8_t(buf, 157, logger_error); + _mav_put_float(buf, 140, battery_voltage); + _mav_put_float(buf, 144, current_consumption); + _mav_put_float(buf, 148, vsupply_5v); + _mav_put_float(buf, 152, temperature); + _mav_put_uint8_t(buf, 156, fmm_state); + _mav_put_uint8_t(buf, 157, nas_state); + _mav_put_uint8_t(buf, 158, wes_state); + _mav_put_uint8_t(buf, 159, gps_fix); + _mav_put_uint8_t(buf, 160, pin_nosecone); + _mav_put_int8_t(buf, 161, logger_error); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN); #else @@ -298,7 +303,8 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin packet.nas_bias_z = nas_bias_z; packet.wes_n = wes_n; packet.wes_e = wes_e; - packet.vbat = vbat; + packet.battery_voltage = battery_voltage; + packet.current_consumption = current_consumption; packet.vsupply_5v = vsupply_5v; packet.temperature = temperature; packet.fmm_state = fmm_state; @@ -360,7 +366,8 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin * @param wes_n [m/s] Wind estimated north velocity * @param wes_e [m/s] Wind estimated east velocity * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected) - * @param vbat [V] Battery voltage + * @param battery_voltage [V] Battery voltage + * @param current_consumption [A] Battery current * @param vsupply_5v [V] Power supply 5V * @param temperature [degC] Temperature * @param logger_error Logger error (0 = no error) @@ -368,7 +375,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin */ static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - uint64_t timestamp,uint8_t fmm_state,uint8_t nas_state,uint8_t wes_state,float pressure_digi,float pressure_static,float airspeed_pitot,float altitude_agl,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float left_servo_angle,float right_servo_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float wes_n,float wes_e,uint8_t pin_nosecone,float vbat,float vsupply_5v,float temperature,int8_t logger_error) + uint64_t timestamp,uint8_t fmm_state,uint8_t nas_state,uint8_t wes_state,float pressure_digi,float pressure_static,float airspeed_pitot,float altitude_agl,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float left_servo_angle,float right_servo_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float wes_n,float wes_e,uint8_t pin_nosecone,float battery_voltage,float current_consumption,float vsupply_5v,float temperature,int8_t logger_error) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN]; @@ -406,15 +413,16 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id _mav_put_float(buf, 128, nas_bias_z); _mav_put_float(buf, 132, wes_n); _mav_put_float(buf, 136, wes_e); - _mav_put_float(buf, 140, vbat); - _mav_put_float(buf, 144, vsupply_5v); - _mav_put_float(buf, 148, temperature); - _mav_put_uint8_t(buf, 152, fmm_state); - _mav_put_uint8_t(buf, 153, nas_state); - _mav_put_uint8_t(buf, 154, wes_state); - _mav_put_uint8_t(buf, 155, gps_fix); - _mav_put_uint8_t(buf, 156, pin_nosecone); - _mav_put_int8_t(buf, 157, logger_error); + _mav_put_float(buf, 140, battery_voltage); + _mav_put_float(buf, 144, current_consumption); + _mav_put_float(buf, 148, vsupply_5v); + _mav_put_float(buf, 152, temperature); + _mav_put_uint8_t(buf, 156, fmm_state); + _mav_put_uint8_t(buf, 157, nas_state); + _mav_put_uint8_t(buf, 158, wes_state); + _mav_put_uint8_t(buf, 159, gps_fix); + _mav_put_uint8_t(buf, 160, pin_nosecone); + _mav_put_int8_t(buf, 161, logger_error); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN); #else @@ -453,7 +461,8 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id packet.nas_bias_z = nas_bias_z; packet.wes_n = wes_n; packet.wes_e = wes_e; - packet.vbat = vbat; + packet.battery_voltage = battery_voltage; + packet.current_consumption = current_consumption; packet.vsupply_5v = vsupply_5v; packet.temperature = temperature; packet.fmm_state = fmm_state; @@ -480,7 +489,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id */ static inline uint16_t mavlink_msg_payload_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm) { - return mavlink_msg_payload_flight_tm_pack(system_id, component_id, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->vbat, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error); + return mavlink_msg_payload_flight_tm_pack(system_id, component_id, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error); } /** @@ -494,7 +503,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_encode(uint8_t system_id, u */ static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm) { - return mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, chan, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->vbat, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error); + return mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, chan, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error); } /** @@ -540,14 +549,15 @@ static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_ * @param wes_n [m/s] Wind estimated north velocity * @param wes_e [m/s] Wind estimated east velocity * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected) - * @param vbat [V] Battery voltage + * @param battery_voltage [V] Battery voltage + * @param current_consumption [A] Battery current * @param vsupply_5v [V] Power supply 5V * @param temperature [degC] Temperature * @param logger_error Logger error (0 = no error) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float vbat, float vsupply_5v, float temperature, int8_t logger_error) +static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float current_consumption, float vsupply_5v, float temperature, int8_t logger_error) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN]; @@ -585,15 +595,16 @@ static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, ui _mav_put_float(buf, 128, nas_bias_z); _mav_put_float(buf, 132, wes_n); _mav_put_float(buf, 136, wes_e); - _mav_put_float(buf, 140, vbat); - _mav_put_float(buf, 144, vsupply_5v); - _mav_put_float(buf, 148, temperature); - _mav_put_uint8_t(buf, 152, fmm_state); - _mav_put_uint8_t(buf, 153, nas_state); - _mav_put_uint8_t(buf, 154, wes_state); - _mav_put_uint8_t(buf, 155, gps_fix); - _mav_put_uint8_t(buf, 156, pin_nosecone); - _mav_put_int8_t(buf, 157, logger_error); + _mav_put_float(buf, 140, battery_voltage); + _mav_put_float(buf, 144, current_consumption); + _mav_put_float(buf, 148, vsupply_5v); + _mav_put_float(buf, 152, temperature); + _mav_put_uint8_t(buf, 156, fmm_state); + _mav_put_uint8_t(buf, 157, nas_state); + _mav_put_uint8_t(buf, 158, wes_state); + _mav_put_uint8_t(buf, 159, gps_fix); + _mav_put_uint8_t(buf, 160, pin_nosecone); + _mav_put_int8_t(buf, 161, logger_error); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC); #else @@ -632,7 +643,8 @@ static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, ui packet.nas_bias_z = nas_bias_z; packet.wes_n = wes_n; packet.wes_e = wes_e; - packet.vbat = vbat; + packet.battery_voltage = battery_voltage; + packet.current_consumption = current_consumption; packet.vsupply_5v = vsupply_5v; packet.temperature = temperature; packet.fmm_state = fmm_state; @@ -654,7 +666,7 @@ static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, ui static inline void mavlink_msg_payload_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_payload_flight_tm_t* payload_flight_tm) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_payload_flight_tm_send(chan, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->vbat, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error); + mavlink_msg_payload_flight_tm_send(chan, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error); #else _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)payload_flight_tm, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC); #endif @@ -668,7 +680,7 @@ static inline void mavlink_msg_payload_flight_tm_send_struct(mavlink_channel_t c is usually the receive buffer for the channel, and allows a reply to an incoming message with minimum stack space usage. */ -static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float vbat, float vsupply_5v, float temperature, int8_t logger_error) +static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float current_consumption, float vsupply_5v, float temperature, int8_t logger_error) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char *buf = (char *)msgbuf; @@ -706,15 +718,16 @@ static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msg _mav_put_float(buf, 128, nas_bias_z); _mav_put_float(buf, 132, wes_n); _mav_put_float(buf, 136, wes_e); - _mav_put_float(buf, 140, vbat); - _mav_put_float(buf, 144, vsupply_5v); - _mav_put_float(buf, 148, temperature); - _mav_put_uint8_t(buf, 152, fmm_state); - _mav_put_uint8_t(buf, 153, nas_state); - _mav_put_uint8_t(buf, 154, wes_state); - _mav_put_uint8_t(buf, 155, gps_fix); - _mav_put_uint8_t(buf, 156, pin_nosecone); - _mav_put_int8_t(buf, 157, logger_error); + _mav_put_float(buf, 140, battery_voltage); + _mav_put_float(buf, 144, current_consumption); + _mav_put_float(buf, 148, vsupply_5v); + _mav_put_float(buf, 152, temperature); + _mav_put_uint8_t(buf, 156, fmm_state); + _mav_put_uint8_t(buf, 157, nas_state); + _mav_put_uint8_t(buf, 158, wes_state); + _mav_put_uint8_t(buf, 159, gps_fix); + _mav_put_uint8_t(buf, 160, pin_nosecone); + _mav_put_int8_t(buf, 161, logger_error); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC); #else @@ -753,7 +766,8 @@ static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msg packet->nas_bias_z = nas_bias_z; packet->wes_n = wes_n; packet->wes_e = wes_e; - packet->vbat = vbat; + packet->battery_voltage = battery_voltage; + packet->current_consumption = current_consumption; packet->vsupply_5v = vsupply_5v; packet->temperature = temperature; packet->fmm_state = fmm_state; @@ -790,7 +804,7 @@ static inline uint64_t mavlink_msg_payload_flight_tm_get_timestamp(const mavlink */ static inline uint8_t mavlink_msg_payload_flight_tm_get_fmm_state(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 152); + return _MAV_RETURN_uint8_t(msg, 156); } /** @@ -800,7 +814,7 @@ static inline uint8_t mavlink_msg_payload_flight_tm_get_fmm_state(const mavlink_ */ static inline uint8_t mavlink_msg_payload_flight_tm_get_nas_state(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 153); + return _MAV_RETURN_uint8_t(msg, 157); } /** @@ -810,7 +824,7 @@ static inline uint8_t mavlink_msg_payload_flight_tm_get_nas_state(const mavlink_ */ static inline uint8_t mavlink_msg_payload_flight_tm_get_wes_state(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 154); + return _MAV_RETURN_uint8_t(msg, 158); } /** @@ -950,7 +964,7 @@ static inline float mavlink_msg_payload_flight_tm_get_mag_z(const mavlink_messag */ static inline uint8_t mavlink_msg_payload_flight_tm_get_gps_fix(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 155); + return _MAV_RETURN_uint8_t(msg, 159); } /** @@ -1160,19 +1174,29 @@ static inline float mavlink_msg_payload_flight_tm_get_wes_e(const mavlink_messag */ static inline uint8_t mavlink_msg_payload_flight_tm_get_pin_nosecone(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 156); + return _MAV_RETURN_uint8_t(msg, 160); } /** - * @brief Get field vbat from payload_flight_tm message + * @brief Get field battery_voltage from payload_flight_tm message * * @return [V] Battery voltage */ -static inline float mavlink_msg_payload_flight_tm_get_vbat(const mavlink_message_t* msg) +static inline float mavlink_msg_payload_flight_tm_get_battery_voltage(const mavlink_message_t* msg) { return _MAV_RETURN_float(msg, 140); } +/** + * @brief Get field current_consumption from payload_flight_tm message + * + * @return [A] Battery current + */ +static inline float mavlink_msg_payload_flight_tm_get_current_consumption(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 144); +} + /** * @brief Get field vsupply_5v from payload_flight_tm message * @@ -1180,7 +1204,7 @@ static inline float mavlink_msg_payload_flight_tm_get_vbat(const mavlink_message */ static inline float mavlink_msg_payload_flight_tm_get_vsupply_5v(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 144); + return _MAV_RETURN_float(msg, 148); } /** @@ -1190,7 +1214,7 @@ static inline float mavlink_msg_payload_flight_tm_get_vsupply_5v(const mavlink_m */ static inline float mavlink_msg_payload_flight_tm_get_temperature(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 148); + return _MAV_RETURN_float(msg, 152); } /** @@ -1200,7 +1224,7 @@ static inline float mavlink_msg_payload_flight_tm_get_temperature(const mavlink_ */ static inline int8_t mavlink_msg_payload_flight_tm_get_logger_error(const mavlink_message_t* msg) { - return _MAV_RETURN_int8_t(msg, 157); + return _MAV_RETURN_int8_t(msg, 161); } /** @@ -1246,7 +1270,8 @@ static inline void mavlink_msg_payload_flight_tm_decode(const mavlink_message_t* payload_flight_tm->nas_bias_z = mavlink_msg_payload_flight_tm_get_nas_bias_z(msg); payload_flight_tm->wes_n = mavlink_msg_payload_flight_tm_get_wes_n(msg); payload_flight_tm->wes_e = mavlink_msg_payload_flight_tm_get_wes_e(msg); - payload_flight_tm->vbat = mavlink_msg_payload_flight_tm_get_vbat(msg); + payload_flight_tm->battery_voltage = mavlink_msg_payload_flight_tm_get_battery_voltage(msg); + payload_flight_tm->current_consumption = mavlink_msg_payload_flight_tm_get_current_consumption(msg); payload_flight_tm->vsupply_5v = mavlink_msg_payload_flight_tm_get_vsupply_5v(msg); payload_flight_tm->temperature = mavlink_msg_payload_flight_tm_get_temperature(msg); payload_flight_tm->fmm_state = mavlink_msg_payload_flight_tm_get_fmm_state(msg); diff --git a/mavlink_lib/gemini/mavlink_msg_rocket_flight_tm.h b/mavlink_lib/gemini/mavlink_msg_rocket_flight_tm.h index 953906c..f5194aa 100644 --- a/mavlink_lib/gemini/mavlink_msg_rocket_flight_tm.h +++ b/mavlink_lib/gemini/mavlink_msg_rocket_flight_tm.h @@ -13,6 +13,7 @@ typedef struct __mavlink_rocket_flight_tm_t { float airspeed_pitot; /*< [m/s] Pitot airspeed*/ float altitude_agl; /*< [m] Altitude above ground level*/ float ada_vert_speed; /*< [m/s] Vertical speed estimated by ADA*/ + float mea_mass; /*< [kg] Mass estimated by MEA*/ float acc_x; /*< [m/s^2] Acceleration on X axis (body)*/ float acc_y; /*< [m/s^2] Acceleration on Y axis (body)*/ float acc_z; /*< [m/s^2] Acceleration on Z axis (body)*/ @@ -26,8 +27,6 @@ typedef struct __mavlink_rocket_flight_tm_t { float gps_lon; /*< [deg] Longitude*/ float gps_alt; /*< [m] GPS Altitude*/ float abk_angle; /*< [deg] Air Brakes angle*/ - float abk_estimated_cd; /*< Estimated drag coefficient*/ - float parachute_load; /*< Parachute load cell value*/ float nas_n; /*< [deg] Navigation system estimated noth position*/ float nas_e; /*< [deg] Navigation system estimated east position*/ float nas_d; /*< [m] Navigation system estimated down position*/ @@ -41,14 +40,15 @@ typedef struct __mavlink_rocket_flight_tm_t { float nas_bias_x; /*< Navigation system gyroscope bias on x axis*/ float nas_bias_y; /*< Navigation system gyroscope bias on y axis*/ float nas_bias_z; /*< Navigation system gyroscope bias on z axis*/ - float estimated_thrust; /*< Estimated thrust from automatic shutdown algorithm*/ - float vbat; /*< [V] Battery voltage*/ + float battery_voltage; /*< [V] Battery voltage*/ + float current_consumption; /*< [A] Battery current*/ float temperature; /*< [degC] Temperature*/ uint8_t ada_state; /*< ADA Controller State*/ uint8_t fmm_state; /*< Flight Mode Manager State*/ uint8_t dpl_state; /*< Deployment Controller State*/ uint8_t abk_state; /*< Airbrake FSM state*/ uint8_t nas_state; /*< Navigation System FSM State*/ + uint8_t mea_state; /*< MEA Controller State*/ uint8_t gps_fix; /*< GPS fix (1 = fix, 0 = no fix)*/ uint8_t pin_launch; /*< Launch pin status (1 = connected, 0 = disconnected)*/ uint8_t pin_nosecone; /*< Nosecone pin status (1 = connected, 0 = disconnected)*/ @@ -57,13 +57,13 @@ typedef struct __mavlink_rocket_flight_tm_t { int8_t logger_error; /*< Logger error (0 = no error, -1 otherwise)*/ } mavlink_rocket_flight_tm_t; -#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN 171 -#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN 171 -#define MAVLINK_MSG_ID_208_LEN 171 -#define MAVLINK_MSG_ID_208_MIN_LEN 171 +#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN 168 +#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN 168 +#define MAVLINK_MSG_ID_208_LEN 168 +#define MAVLINK_MSG_ID_208_MIN_LEN 168 -#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC 141 -#define MAVLINK_MSG_ID_208_CRC 141 +#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC 254 +#define MAVLINK_MSG_ID_208_CRC 254 @@ -73,11 +73,12 @@ typedef struct __mavlink_rocket_flight_tm_t { "ROCKET_FLIGHT_TM", \ 50, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \ - { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \ - { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \ - { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \ - { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \ - { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \ + { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \ + { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \ + { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \ + { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \ + { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \ + { "mea_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_rocket_flight_tm_t, mea_state) }, \ { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rocket_flight_tm_t, pressure_ada) }, \ { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rocket_flight_tm_t, pressure_digi) }, \ { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rocket_flight_tm_t, pressure_static) }, \ @@ -85,43 +86,42 @@ typedef struct __mavlink_rocket_flight_tm_t { { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_rocket_flight_tm_t, airspeed_pitot) }, \ { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_rocket_flight_tm_t, altitude_agl) }, \ { "ada_vert_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_rocket_flight_tm_t, ada_vert_speed) }, \ - { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_rocket_flight_tm_t, acc_x) }, \ - { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_flight_tm_t, acc_y) }, \ - { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_flight_tm_t, acc_z) }, \ - { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_flight_tm_t, gyro_x) }, \ - { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_flight_tm_t, gyro_y) }, \ - { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_flight_tm_t, gyro_z) }, \ - { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \ - { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \ - { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \ - { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \ - { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \ - { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \ - { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \ - { "abk_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, abk_angle) }, \ - { "abk_estimated_cd", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_rocket_flight_tm_t, abk_estimated_cd) }, \ - { "parachute_load", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, parachute_load) }, \ - { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \ - { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \ - { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \ - { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \ - { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \ - { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \ - { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \ - { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \ - { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \ - { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \ - { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \ - { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \ - { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \ - { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \ - { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \ - { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \ - { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \ - { "estimated_thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, estimated_thrust) }, \ - { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, vbat) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \ - { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 170, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \ + { "mea_mass", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_rocket_flight_tm_t, mea_mass) }, \ + { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_flight_tm_t, acc_x) }, \ + { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_flight_tm_t, acc_y) }, \ + { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_flight_tm_t, acc_z) }, \ + { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_flight_tm_t, gyro_x) }, \ + { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_flight_tm_t, gyro_y) }, \ + { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_flight_tm_t, gyro_z) }, \ + { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \ + { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \ + { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \ + { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \ + { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \ + { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \ + { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \ + { "abk_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_rocket_flight_tm_t, abk_angle) }, \ + { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \ + { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \ + { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \ + { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \ + { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \ + { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \ + { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \ + { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \ + { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \ + { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \ + { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \ + { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \ + { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \ + { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \ + { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \ + { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \ + { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \ + { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, battery_voltage) }, \ + { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, current_consumption) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \ + { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \ } \ } #else @@ -129,11 +129,12 @@ typedef struct __mavlink_rocket_flight_tm_t { "ROCKET_FLIGHT_TM", \ 50, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \ - { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \ - { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \ - { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \ - { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \ - { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \ + { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \ + { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \ + { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \ + { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \ + { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \ + { "mea_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_rocket_flight_tm_t, mea_state) }, \ { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rocket_flight_tm_t, pressure_ada) }, \ { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rocket_flight_tm_t, pressure_digi) }, \ { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rocket_flight_tm_t, pressure_static) }, \ @@ -141,43 +142,42 @@ typedef struct __mavlink_rocket_flight_tm_t { { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_rocket_flight_tm_t, airspeed_pitot) }, \ { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_rocket_flight_tm_t, altitude_agl) }, \ { "ada_vert_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_rocket_flight_tm_t, ada_vert_speed) }, \ - { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_rocket_flight_tm_t, acc_x) }, \ - { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_flight_tm_t, acc_y) }, \ - { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_flight_tm_t, acc_z) }, \ - { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_flight_tm_t, gyro_x) }, \ - { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_flight_tm_t, gyro_y) }, \ - { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_flight_tm_t, gyro_z) }, \ - { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \ - { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \ - { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \ - { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \ - { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \ - { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \ - { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \ - { "abk_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, abk_angle) }, \ - { "abk_estimated_cd", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_rocket_flight_tm_t, abk_estimated_cd) }, \ - { "parachute_load", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, parachute_load) }, \ - { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \ - { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \ - { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \ - { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \ - { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \ - { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \ - { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \ - { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \ - { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \ - { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \ - { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \ - { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \ - { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \ - { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \ - { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \ - { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \ - { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \ - { "estimated_thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, estimated_thrust) }, \ - { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, vbat) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \ - { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 170, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \ + { "mea_mass", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_rocket_flight_tm_t, mea_mass) }, \ + { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_flight_tm_t, acc_x) }, \ + { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_flight_tm_t, acc_y) }, \ + { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_flight_tm_t, acc_z) }, \ + { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_flight_tm_t, gyro_x) }, \ + { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_flight_tm_t, gyro_y) }, \ + { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_flight_tm_t, gyro_z) }, \ + { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \ + { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \ + { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \ + { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \ + { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \ + { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \ + { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \ + { "abk_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_rocket_flight_tm_t, abk_angle) }, \ + { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \ + { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \ + { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \ + { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \ + { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \ + { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \ + { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \ + { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \ + { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \ + { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \ + { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \ + { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \ + { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \ + { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \ + { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \ + { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \ + { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \ + { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, battery_voltage) }, \ + { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, current_consumption) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \ + { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \ } \ } #endif @@ -194,6 +194,7 @@ typedef struct __mavlink_rocket_flight_tm_t { * @param dpl_state Deployment Controller State * @param abk_state Airbrake FSM state * @param nas_state Navigation System FSM State + * @param mea_state MEA Controller State * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA * @param pressure_digi [Pa] Pressure from digital sensor * @param pressure_static [Pa] Pressure from static port @@ -201,6 +202,7 @@ typedef struct __mavlink_rocket_flight_tm_t { * @param airspeed_pitot [m/s] Pitot airspeed * @param altitude_agl [m] Altitude above ground level * @param ada_vert_speed [m/s] Vertical speed estimated by ADA + * @param mea_mass [kg] Mass estimated by MEA * @param acc_x [m/s^2] Acceleration on X axis (body) * @param acc_y [m/s^2] Acceleration on Y axis (body) * @param acc_z [m/s^2] Acceleration on Z axis (body) @@ -215,8 +217,6 @@ typedef struct __mavlink_rocket_flight_tm_t { * @param gps_lon [deg] Longitude * @param gps_alt [m] GPS Altitude * @param abk_angle [deg] Air Brakes angle - * @param abk_estimated_cd Estimated drag coefficient - * @param parachute_load Parachute load cell value * @param nas_n [deg] Navigation system estimated noth position * @param nas_e [deg] Navigation system estimated east position * @param nas_d [m] Navigation system estimated down position @@ -234,14 +234,14 @@ typedef struct __mavlink_rocket_flight_tm_t { * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected) * @param pin_expulsion Servo sensor status (1 = actuated, 0 = idle) * @param cutter_presence Cutter presence status (1 = present, 0 = missing) - * @param estimated_thrust Estimated thrust from automatic shutdown algorithm - * @param vbat [V] Battery voltage + * @param battery_voltage [V] Battery voltage + * @param current_consumption [A] Battery current * @param temperature [degC] Temperature * @param logger_error Logger error (0 = no error, -1 otherwise) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float abk_estimated_cd, float parachute_load, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float estimated_thrust, float vbat, float temperature, int8_t logger_error) + uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float current_consumption, float temperature, int8_t logger_error) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN]; @@ -253,48 +253,48 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint _mav_put_float(buf, 24, airspeed_pitot); _mav_put_float(buf, 28, altitude_agl); _mav_put_float(buf, 32, ada_vert_speed); - _mav_put_float(buf, 36, acc_x); - _mav_put_float(buf, 40, acc_y); - _mav_put_float(buf, 44, acc_z); - _mav_put_float(buf, 48, gyro_x); - _mav_put_float(buf, 52, gyro_y); - _mav_put_float(buf, 56, gyro_z); - _mav_put_float(buf, 60, mag_x); - _mav_put_float(buf, 64, mag_y); - _mav_put_float(buf, 68, mag_z); - _mav_put_float(buf, 72, gps_lat); - _mav_put_float(buf, 76, gps_lon); - _mav_put_float(buf, 80, gps_alt); - _mav_put_float(buf, 84, abk_angle); - _mav_put_float(buf, 88, abk_estimated_cd); - _mav_put_float(buf, 92, parachute_load); - _mav_put_float(buf, 96, nas_n); - _mav_put_float(buf, 100, nas_e); - _mav_put_float(buf, 104, nas_d); - _mav_put_float(buf, 108, nas_vn); - _mav_put_float(buf, 112, nas_ve); - _mav_put_float(buf, 116, nas_vd); - _mav_put_float(buf, 120, nas_qx); - _mav_put_float(buf, 124, nas_qy); - _mav_put_float(buf, 128, nas_qz); - _mav_put_float(buf, 132, nas_qw); - _mav_put_float(buf, 136, nas_bias_x); - _mav_put_float(buf, 140, nas_bias_y); - _mav_put_float(buf, 144, nas_bias_z); - _mav_put_float(buf, 148, estimated_thrust); - _mav_put_float(buf, 152, vbat); - _mav_put_float(buf, 156, temperature); - _mav_put_uint8_t(buf, 160, ada_state); - _mav_put_uint8_t(buf, 161, fmm_state); - _mav_put_uint8_t(buf, 162, dpl_state); - _mav_put_uint8_t(buf, 163, abk_state); - _mav_put_uint8_t(buf, 164, nas_state); - _mav_put_uint8_t(buf, 165, gps_fix); - _mav_put_uint8_t(buf, 166, pin_launch); - _mav_put_uint8_t(buf, 167, pin_nosecone); - _mav_put_uint8_t(buf, 168, pin_expulsion); - _mav_put_uint8_t(buf, 169, cutter_presence); - _mav_put_int8_t(buf, 170, logger_error); + _mav_put_float(buf, 36, mea_mass); + _mav_put_float(buf, 40, acc_x); + _mav_put_float(buf, 44, acc_y); + _mav_put_float(buf, 48, acc_z); + _mav_put_float(buf, 52, gyro_x); + _mav_put_float(buf, 56, gyro_y); + _mav_put_float(buf, 60, gyro_z); + _mav_put_float(buf, 64, mag_x); + _mav_put_float(buf, 68, mag_y); + _mav_put_float(buf, 72, mag_z); + _mav_put_float(buf, 76, gps_lat); + _mav_put_float(buf, 80, gps_lon); + _mav_put_float(buf, 84, gps_alt); + _mav_put_float(buf, 88, abk_angle); + _mav_put_float(buf, 92, nas_n); + _mav_put_float(buf, 96, nas_e); + _mav_put_float(buf, 100, nas_d); + _mav_put_float(buf, 104, nas_vn); + _mav_put_float(buf, 108, nas_ve); + _mav_put_float(buf, 112, nas_vd); + _mav_put_float(buf, 116, nas_qx); + _mav_put_float(buf, 120, nas_qy); + _mav_put_float(buf, 124, nas_qz); + _mav_put_float(buf, 128, nas_qw); + _mav_put_float(buf, 132, nas_bias_x); + _mav_put_float(buf, 136, nas_bias_y); + _mav_put_float(buf, 140, nas_bias_z); + _mav_put_float(buf, 144, battery_voltage); + _mav_put_float(buf, 148, current_consumption); + _mav_put_float(buf, 152, temperature); + _mav_put_uint8_t(buf, 156, ada_state); + _mav_put_uint8_t(buf, 157, fmm_state); + _mav_put_uint8_t(buf, 158, dpl_state); + _mav_put_uint8_t(buf, 159, abk_state); + _mav_put_uint8_t(buf, 160, nas_state); + _mav_put_uint8_t(buf, 161, mea_state); + _mav_put_uint8_t(buf, 162, gps_fix); + _mav_put_uint8_t(buf, 163, pin_launch); + _mav_put_uint8_t(buf, 164, pin_nosecone); + _mav_put_uint8_t(buf, 165, pin_expulsion); + _mav_put_uint8_t(buf, 166, cutter_presence); + _mav_put_int8_t(buf, 167, logger_error); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN); #else @@ -307,6 +307,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint packet.airspeed_pitot = airspeed_pitot; packet.altitude_agl = altitude_agl; packet.ada_vert_speed = ada_vert_speed; + packet.mea_mass = mea_mass; packet.acc_x = acc_x; packet.acc_y = acc_y; packet.acc_z = acc_z; @@ -320,8 +321,6 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint packet.gps_lon = gps_lon; packet.gps_alt = gps_alt; packet.abk_angle = abk_angle; - packet.abk_estimated_cd = abk_estimated_cd; - packet.parachute_load = parachute_load; packet.nas_n = nas_n; packet.nas_e = nas_e; packet.nas_d = nas_d; @@ -335,14 +334,15 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint packet.nas_bias_x = nas_bias_x; packet.nas_bias_y = nas_bias_y; packet.nas_bias_z = nas_bias_z; - packet.estimated_thrust = estimated_thrust; - packet.vbat = vbat; + packet.battery_voltage = battery_voltage; + packet.current_consumption = current_consumption; packet.temperature = temperature; packet.ada_state = ada_state; packet.fmm_state = fmm_state; packet.dpl_state = dpl_state; packet.abk_state = abk_state; packet.nas_state = nas_state; + packet.mea_state = mea_state; packet.gps_fix = gps_fix; packet.pin_launch = pin_launch; packet.pin_nosecone = pin_nosecone; @@ -369,6 +369,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint * @param dpl_state Deployment Controller State * @param abk_state Airbrake FSM state * @param nas_state Navigation System FSM State + * @param mea_state MEA Controller State * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA * @param pressure_digi [Pa] Pressure from digital sensor * @param pressure_static [Pa] Pressure from static port @@ -376,6 +377,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint * @param airspeed_pitot [m/s] Pitot airspeed * @param altitude_agl [m] Altitude above ground level * @param ada_vert_speed [m/s] Vertical speed estimated by ADA + * @param mea_mass [kg] Mass estimated by MEA * @param acc_x [m/s^2] Acceleration on X axis (body) * @param acc_y [m/s^2] Acceleration on Y axis (body) * @param acc_z [m/s^2] Acceleration on Z axis (body) @@ -390,8 +392,6 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint * @param gps_lon [deg] Longitude * @param gps_alt [m] GPS Altitude * @param abk_angle [deg] Air Brakes angle - * @param abk_estimated_cd Estimated drag coefficient - * @param parachute_load Parachute load cell value * @param nas_n [deg] Navigation system estimated noth position * @param nas_e [deg] Navigation system estimated east position * @param nas_d [m] Navigation system estimated down position @@ -409,15 +409,15 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected) * @param pin_expulsion Servo sensor status (1 = actuated, 0 = idle) * @param cutter_presence Cutter presence status (1 = present, 0 = missing) - * @param estimated_thrust Estimated thrust from automatic shutdown algorithm - * @param vbat [V] Battery voltage + * @param battery_voltage [V] Battery voltage + * @param current_consumption [A] Battery current * @param temperature [degC] Temperature * @param logger_error Logger error (0 = no error, -1 otherwise) * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - uint64_t timestamp,uint8_t ada_state,uint8_t fmm_state,uint8_t dpl_state,uint8_t abk_state,uint8_t nas_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float ada_vert_speed,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float abk_angle,float abk_estimated_cd,float parachute_load,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t pin_expulsion,uint8_t cutter_presence,float estimated_thrust,float vbat,float temperature,int8_t logger_error) + uint64_t timestamp,uint8_t ada_state,uint8_t fmm_state,uint8_t dpl_state,uint8_t abk_state,uint8_t nas_state,uint8_t mea_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float ada_vert_speed,float mea_mass,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float abk_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t pin_expulsion,uint8_t cutter_presence,float battery_voltage,float current_consumption,float temperature,int8_t logger_error) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN]; @@ -429,48 +429,48 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id, _mav_put_float(buf, 24, airspeed_pitot); _mav_put_float(buf, 28, altitude_agl); _mav_put_float(buf, 32, ada_vert_speed); - _mav_put_float(buf, 36, acc_x); - _mav_put_float(buf, 40, acc_y); - _mav_put_float(buf, 44, acc_z); - _mav_put_float(buf, 48, gyro_x); - _mav_put_float(buf, 52, gyro_y); - _mav_put_float(buf, 56, gyro_z); - _mav_put_float(buf, 60, mag_x); - _mav_put_float(buf, 64, mag_y); - _mav_put_float(buf, 68, mag_z); - _mav_put_float(buf, 72, gps_lat); - _mav_put_float(buf, 76, gps_lon); - _mav_put_float(buf, 80, gps_alt); - _mav_put_float(buf, 84, abk_angle); - _mav_put_float(buf, 88, abk_estimated_cd); - _mav_put_float(buf, 92, parachute_load); - _mav_put_float(buf, 96, nas_n); - _mav_put_float(buf, 100, nas_e); - _mav_put_float(buf, 104, nas_d); - _mav_put_float(buf, 108, nas_vn); - _mav_put_float(buf, 112, nas_ve); - _mav_put_float(buf, 116, nas_vd); - _mav_put_float(buf, 120, nas_qx); - _mav_put_float(buf, 124, nas_qy); - _mav_put_float(buf, 128, nas_qz); - _mav_put_float(buf, 132, nas_qw); - _mav_put_float(buf, 136, nas_bias_x); - _mav_put_float(buf, 140, nas_bias_y); - _mav_put_float(buf, 144, nas_bias_z); - _mav_put_float(buf, 148, estimated_thrust); - _mav_put_float(buf, 152, vbat); - _mav_put_float(buf, 156, temperature); - _mav_put_uint8_t(buf, 160, ada_state); - _mav_put_uint8_t(buf, 161, fmm_state); - _mav_put_uint8_t(buf, 162, dpl_state); - _mav_put_uint8_t(buf, 163, abk_state); - _mav_put_uint8_t(buf, 164, nas_state); - _mav_put_uint8_t(buf, 165, gps_fix); - _mav_put_uint8_t(buf, 166, pin_launch); - _mav_put_uint8_t(buf, 167, pin_nosecone); - _mav_put_uint8_t(buf, 168, pin_expulsion); - _mav_put_uint8_t(buf, 169, cutter_presence); - _mav_put_int8_t(buf, 170, logger_error); + _mav_put_float(buf, 36, mea_mass); + _mav_put_float(buf, 40, acc_x); + _mav_put_float(buf, 44, acc_y); + _mav_put_float(buf, 48, acc_z); + _mav_put_float(buf, 52, gyro_x); + _mav_put_float(buf, 56, gyro_y); + _mav_put_float(buf, 60, gyro_z); + _mav_put_float(buf, 64, mag_x); + _mav_put_float(buf, 68, mag_y); + _mav_put_float(buf, 72, mag_z); + _mav_put_float(buf, 76, gps_lat); + _mav_put_float(buf, 80, gps_lon); + _mav_put_float(buf, 84, gps_alt); + _mav_put_float(buf, 88, abk_angle); + _mav_put_float(buf, 92, nas_n); + _mav_put_float(buf, 96, nas_e); + _mav_put_float(buf, 100, nas_d); + _mav_put_float(buf, 104, nas_vn); + _mav_put_float(buf, 108, nas_ve); + _mav_put_float(buf, 112, nas_vd); + _mav_put_float(buf, 116, nas_qx); + _mav_put_float(buf, 120, nas_qy); + _mav_put_float(buf, 124, nas_qz); + _mav_put_float(buf, 128, nas_qw); + _mav_put_float(buf, 132, nas_bias_x); + _mav_put_float(buf, 136, nas_bias_y); + _mav_put_float(buf, 140, nas_bias_z); + _mav_put_float(buf, 144, battery_voltage); + _mav_put_float(buf, 148, current_consumption); + _mav_put_float(buf, 152, temperature); + _mav_put_uint8_t(buf, 156, ada_state); + _mav_put_uint8_t(buf, 157, fmm_state); + _mav_put_uint8_t(buf, 158, dpl_state); + _mav_put_uint8_t(buf, 159, abk_state); + _mav_put_uint8_t(buf, 160, nas_state); + _mav_put_uint8_t(buf, 161, mea_state); + _mav_put_uint8_t(buf, 162, gps_fix); + _mav_put_uint8_t(buf, 163, pin_launch); + _mav_put_uint8_t(buf, 164, pin_nosecone); + _mav_put_uint8_t(buf, 165, pin_expulsion); + _mav_put_uint8_t(buf, 166, cutter_presence); + _mav_put_int8_t(buf, 167, logger_error); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN); #else @@ -483,6 +483,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id, packet.airspeed_pitot = airspeed_pitot; packet.altitude_agl = altitude_agl; packet.ada_vert_speed = ada_vert_speed; + packet.mea_mass = mea_mass; packet.acc_x = acc_x; packet.acc_y = acc_y; packet.acc_z = acc_z; @@ -496,8 +497,6 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id, packet.gps_lon = gps_lon; packet.gps_alt = gps_alt; packet.abk_angle = abk_angle; - packet.abk_estimated_cd = abk_estimated_cd; - packet.parachute_load = parachute_load; packet.nas_n = nas_n; packet.nas_e = nas_e; packet.nas_d = nas_d; @@ -511,14 +510,15 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id, packet.nas_bias_x = nas_bias_x; packet.nas_bias_y = nas_bias_y; packet.nas_bias_z = nas_bias_z; - packet.estimated_thrust = estimated_thrust; - packet.vbat = vbat; + packet.battery_voltage = battery_voltage; + packet.current_consumption = current_consumption; packet.temperature = temperature; packet.ada_state = ada_state; packet.fmm_state = fmm_state; packet.dpl_state = dpl_state; packet.abk_state = abk_state; packet.nas_state = nas_state; + packet.mea_state = mea_state; packet.gps_fix = gps_fix; packet.pin_launch = pin_launch; packet.pin_nosecone = pin_nosecone; @@ -543,7 +543,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id, */ static inline uint16_t mavlink_msg_rocket_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm) { - return mavlink_msg_rocket_flight_tm_pack(system_id, component_id, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->abk_estimated_cd, rocket_flight_tm->parachute_load, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->estimated_thrust, rocket_flight_tm->vbat, rocket_flight_tm->temperature, rocket_flight_tm->logger_error); + return mavlink_msg_rocket_flight_tm_pack(system_id, component_id, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error); } /** @@ -557,7 +557,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode(uint8_t system_id, ui */ static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm) { - return mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, chan, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->abk_estimated_cd, rocket_flight_tm->parachute_load, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->estimated_thrust, rocket_flight_tm->vbat, rocket_flight_tm->temperature, rocket_flight_tm->logger_error); + return mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, chan, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error); } /** @@ -570,6 +570,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_i * @param dpl_state Deployment Controller State * @param abk_state Airbrake FSM state * @param nas_state Navigation System FSM State + * @param mea_state MEA Controller State * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA * @param pressure_digi [Pa] Pressure from digital sensor * @param pressure_static [Pa] Pressure from static port @@ -577,6 +578,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_i * @param airspeed_pitot [m/s] Pitot airspeed * @param altitude_agl [m] Altitude above ground level * @param ada_vert_speed [m/s] Vertical speed estimated by ADA + * @param mea_mass [kg] Mass estimated by MEA * @param acc_x [m/s^2] Acceleration on X axis (body) * @param acc_y [m/s^2] Acceleration on Y axis (body) * @param acc_z [m/s^2] Acceleration on Z axis (body) @@ -591,8 +593,6 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_i * @param gps_lon [deg] Longitude * @param gps_alt [m] GPS Altitude * @param abk_angle [deg] Air Brakes angle - * @param abk_estimated_cd Estimated drag coefficient - * @param parachute_load Parachute load cell value * @param nas_n [deg] Navigation system estimated noth position * @param nas_e [deg] Navigation system estimated east position * @param nas_d [m] Navigation system estimated down position @@ -610,14 +610,14 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_i * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected) * @param pin_expulsion Servo sensor status (1 = actuated, 0 = idle) * @param cutter_presence Cutter presence status (1 = present, 0 = missing) - * @param estimated_thrust Estimated thrust from automatic shutdown algorithm - * @param vbat [V] Battery voltage + * @param battery_voltage [V] Battery voltage + * @param current_consumption [A] Battery current * @param temperature [degC] Temperature * @param logger_error Logger error (0 = no error, -1 otherwise) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float abk_estimated_cd, float parachute_load, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float estimated_thrust, float vbat, float temperature, int8_t logger_error) +static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float current_consumption, float temperature, int8_t logger_error) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN]; @@ -629,48 +629,48 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin _mav_put_float(buf, 24, airspeed_pitot); _mav_put_float(buf, 28, altitude_agl); _mav_put_float(buf, 32, ada_vert_speed); - _mav_put_float(buf, 36, acc_x); - _mav_put_float(buf, 40, acc_y); - _mav_put_float(buf, 44, acc_z); - _mav_put_float(buf, 48, gyro_x); - _mav_put_float(buf, 52, gyro_y); - _mav_put_float(buf, 56, gyro_z); - _mav_put_float(buf, 60, mag_x); - _mav_put_float(buf, 64, mag_y); - _mav_put_float(buf, 68, mag_z); - _mav_put_float(buf, 72, gps_lat); - _mav_put_float(buf, 76, gps_lon); - _mav_put_float(buf, 80, gps_alt); - _mav_put_float(buf, 84, abk_angle); - _mav_put_float(buf, 88, abk_estimated_cd); - _mav_put_float(buf, 92, parachute_load); - _mav_put_float(buf, 96, nas_n); - _mav_put_float(buf, 100, nas_e); - _mav_put_float(buf, 104, nas_d); - _mav_put_float(buf, 108, nas_vn); - _mav_put_float(buf, 112, nas_ve); - _mav_put_float(buf, 116, nas_vd); - _mav_put_float(buf, 120, nas_qx); - _mav_put_float(buf, 124, nas_qy); - _mav_put_float(buf, 128, nas_qz); - _mav_put_float(buf, 132, nas_qw); - _mav_put_float(buf, 136, nas_bias_x); - _mav_put_float(buf, 140, nas_bias_y); - _mav_put_float(buf, 144, nas_bias_z); - _mav_put_float(buf, 148, estimated_thrust); - _mav_put_float(buf, 152, vbat); - _mav_put_float(buf, 156, temperature); - _mav_put_uint8_t(buf, 160, ada_state); - _mav_put_uint8_t(buf, 161, fmm_state); - _mav_put_uint8_t(buf, 162, dpl_state); - _mav_put_uint8_t(buf, 163, abk_state); - _mav_put_uint8_t(buf, 164, nas_state); - _mav_put_uint8_t(buf, 165, gps_fix); - _mav_put_uint8_t(buf, 166, pin_launch); - _mav_put_uint8_t(buf, 167, pin_nosecone); - _mav_put_uint8_t(buf, 168, pin_expulsion); - _mav_put_uint8_t(buf, 169, cutter_presence); - _mav_put_int8_t(buf, 170, logger_error); + _mav_put_float(buf, 36, mea_mass); + _mav_put_float(buf, 40, acc_x); + _mav_put_float(buf, 44, acc_y); + _mav_put_float(buf, 48, acc_z); + _mav_put_float(buf, 52, gyro_x); + _mav_put_float(buf, 56, gyro_y); + _mav_put_float(buf, 60, gyro_z); + _mav_put_float(buf, 64, mag_x); + _mav_put_float(buf, 68, mag_y); + _mav_put_float(buf, 72, mag_z); + _mav_put_float(buf, 76, gps_lat); + _mav_put_float(buf, 80, gps_lon); + _mav_put_float(buf, 84, gps_alt); + _mav_put_float(buf, 88, abk_angle); + _mav_put_float(buf, 92, nas_n); + _mav_put_float(buf, 96, nas_e); + _mav_put_float(buf, 100, nas_d); + _mav_put_float(buf, 104, nas_vn); + _mav_put_float(buf, 108, nas_ve); + _mav_put_float(buf, 112, nas_vd); + _mav_put_float(buf, 116, nas_qx); + _mav_put_float(buf, 120, nas_qy); + _mav_put_float(buf, 124, nas_qz); + _mav_put_float(buf, 128, nas_qw); + _mav_put_float(buf, 132, nas_bias_x); + _mav_put_float(buf, 136, nas_bias_y); + _mav_put_float(buf, 140, nas_bias_z); + _mav_put_float(buf, 144, battery_voltage); + _mav_put_float(buf, 148, current_consumption); + _mav_put_float(buf, 152, temperature); + _mav_put_uint8_t(buf, 156, ada_state); + _mav_put_uint8_t(buf, 157, fmm_state); + _mav_put_uint8_t(buf, 158, dpl_state); + _mav_put_uint8_t(buf, 159, abk_state); + _mav_put_uint8_t(buf, 160, nas_state); + _mav_put_uint8_t(buf, 161, mea_state); + _mav_put_uint8_t(buf, 162, gps_fix); + _mav_put_uint8_t(buf, 163, pin_launch); + _mav_put_uint8_t(buf, 164, pin_nosecone); + _mav_put_uint8_t(buf, 165, pin_expulsion); + _mav_put_uint8_t(buf, 166, cutter_presence); + _mav_put_int8_t(buf, 167, logger_error); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC); #else @@ -683,6 +683,7 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin packet.airspeed_pitot = airspeed_pitot; packet.altitude_agl = altitude_agl; packet.ada_vert_speed = ada_vert_speed; + packet.mea_mass = mea_mass; packet.acc_x = acc_x; packet.acc_y = acc_y; packet.acc_z = acc_z; @@ -696,8 +697,6 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin packet.gps_lon = gps_lon; packet.gps_alt = gps_alt; packet.abk_angle = abk_angle; - packet.abk_estimated_cd = abk_estimated_cd; - packet.parachute_load = parachute_load; packet.nas_n = nas_n; packet.nas_e = nas_e; packet.nas_d = nas_d; @@ -711,14 +710,15 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin packet.nas_bias_x = nas_bias_x; packet.nas_bias_y = nas_bias_y; packet.nas_bias_z = nas_bias_z; - packet.estimated_thrust = estimated_thrust; - packet.vbat = vbat; + packet.battery_voltage = battery_voltage; + packet.current_consumption = current_consumption; packet.temperature = temperature; packet.ada_state = ada_state; packet.fmm_state = fmm_state; packet.dpl_state = dpl_state; packet.abk_state = abk_state; packet.nas_state = nas_state; + packet.mea_state = mea_state; packet.gps_fix = gps_fix; packet.pin_launch = pin_launch; packet.pin_nosecone = pin_nosecone; @@ -738,7 +738,7 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin static inline void mavlink_msg_rocket_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_rocket_flight_tm_t* rocket_flight_tm) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rocket_flight_tm_send(chan, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->abk_estimated_cd, rocket_flight_tm->parachute_load, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->estimated_thrust, rocket_flight_tm->vbat, rocket_flight_tm->temperature, rocket_flight_tm->logger_error); + mavlink_msg_rocket_flight_tm_send(chan, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error); #else _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)rocket_flight_tm, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC); #endif @@ -752,7 +752,7 @@ static inline void mavlink_msg_rocket_flight_tm_send_struct(mavlink_channel_t ch is usually the receive buffer for the channel, and allows a reply to an incoming message with minimum stack space usage. */ -static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float abk_estimated_cd, float parachute_load, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float estimated_thrust, float vbat, float temperature, int8_t logger_error) +static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float current_consumption, float temperature, int8_t logger_error) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char *buf = (char *)msgbuf; @@ -764,48 +764,48 @@ static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgb _mav_put_float(buf, 24, airspeed_pitot); _mav_put_float(buf, 28, altitude_agl); _mav_put_float(buf, 32, ada_vert_speed); - _mav_put_float(buf, 36, acc_x); - _mav_put_float(buf, 40, acc_y); - _mav_put_float(buf, 44, acc_z); - _mav_put_float(buf, 48, gyro_x); - _mav_put_float(buf, 52, gyro_y); - _mav_put_float(buf, 56, gyro_z); - _mav_put_float(buf, 60, mag_x); - _mav_put_float(buf, 64, mag_y); - _mav_put_float(buf, 68, mag_z); - _mav_put_float(buf, 72, gps_lat); - _mav_put_float(buf, 76, gps_lon); - _mav_put_float(buf, 80, gps_alt); - _mav_put_float(buf, 84, abk_angle); - _mav_put_float(buf, 88, abk_estimated_cd); - _mav_put_float(buf, 92, parachute_load); - _mav_put_float(buf, 96, nas_n); - _mav_put_float(buf, 100, nas_e); - _mav_put_float(buf, 104, nas_d); - _mav_put_float(buf, 108, nas_vn); - _mav_put_float(buf, 112, nas_ve); - _mav_put_float(buf, 116, nas_vd); - _mav_put_float(buf, 120, nas_qx); - _mav_put_float(buf, 124, nas_qy); - _mav_put_float(buf, 128, nas_qz); - _mav_put_float(buf, 132, nas_qw); - _mav_put_float(buf, 136, nas_bias_x); - _mav_put_float(buf, 140, nas_bias_y); - _mav_put_float(buf, 144, nas_bias_z); - _mav_put_float(buf, 148, estimated_thrust); - _mav_put_float(buf, 152, vbat); - _mav_put_float(buf, 156, temperature); - _mav_put_uint8_t(buf, 160, ada_state); - _mav_put_uint8_t(buf, 161, fmm_state); - _mav_put_uint8_t(buf, 162, dpl_state); - _mav_put_uint8_t(buf, 163, abk_state); - _mav_put_uint8_t(buf, 164, nas_state); - _mav_put_uint8_t(buf, 165, gps_fix); - _mav_put_uint8_t(buf, 166, pin_launch); - _mav_put_uint8_t(buf, 167, pin_nosecone); - _mav_put_uint8_t(buf, 168, pin_expulsion); - _mav_put_uint8_t(buf, 169, cutter_presence); - _mav_put_int8_t(buf, 170, logger_error); + _mav_put_float(buf, 36, mea_mass); + _mav_put_float(buf, 40, acc_x); + _mav_put_float(buf, 44, acc_y); + _mav_put_float(buf, 48, acc_z); + _mav_put_float(buf, 52, gyro_x); + _mav_put_float(buf, 56, gyro_y); + _mav_put_float(buf, 60, gyro_z); + _mav_put_float(buf, 64, mag_x); + _mav_put_float(buf, 68, mag_y); + _mav_put_float(buf, 72, mag_z); + _mav_put_float(buf, 76, gps_lat); + _mav_put_float(buf, 80, gps_lon); + _mav_put_float(buf, 84, gps_alt); + _mav_put_float(buf, 88, abk_angle); + _mav_put_float(buf, 92, nas_n); + _mav_put_float(buf, 96, nas_e); + _mav_put_float(buf, 100, nas_d); + _mav_put_float(buf, 104, nas_vn); + _mav_put_float(buf, 108, nas_ve); + _mav_put_float(buf, 112, nas_vd); + _mav_put_float(buf, 116, nas_qx); + _mav_put_float(buf, 120, nas_qy); + _mav_put_float(buf, 124, nas_qz); + _mav_put_float(buf, 128, nas_qw); + _mav_put_float(buf, 132, nas_bias_x); + _mav_put_float(buf, 136, nas_bias_y); + _mav_put_float(buf, 140, nas_bias_z); + _mav_put_float(buf, 144, battery_voltage); + _mav_put_float(buf, 148, current_consumption); + _mav_put_float(buf, 152, temperature); + _mav_put_uint8_t(buf, 156, ada_state); + _mav_put_uint8_t(buf, 157, fmm_state); + _mav_put_uint8_t(buf, 158, dpl_state); + _mav_put_uint8_t(buf, 159, abk_state); + _mav_put_uint8_t(buf, 160, nas_state); + _mav_put_uint8_t(buf, 161, mea_state); + _mav_put_uint8_t(buf, 162, gps_fix); + _mav_put_uint8_t(buf, 163, pin_launch); + _mav_put_uint8_t(buf, 164, pin_nosecone); + _mav_put_uint8_t(buf, 165, pin_expulsion); + _mav_put_uint8_t(buf, 166, cutter_presence); + _mav_put_int8_t(buf, 167, logger_error); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC); #else @@ -818,6 +818,7 @@ static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgb packet->airspeed_pitot = airspeed_pitot; packet->altitude_agl = altitude_agl; packet->ada_vert_speed = ada_vert_speed; + packet->mea_mass = mea_mass; packet->acc_x = acc_x; packet->acc_y = acc_y; packet->acc_z = acc_z; @@ -831,8 +832,6 @@ static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgb packet->gps_lon = gps_lon; packet->gps_alt = gps_alt; packet->abk_angle = abk_angle; - packet->abk_estimated_cd = abk_estimated_cd; - packet->parachute_load = parachute_load; packet->nas_n = nas_n; packet->nas_e = nas_e; packet->nas_d = nas_d; @@ -846,14 +845,15 @@ static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgb packet->nas_bias_x = nas_bias_x; packet->nas_bias_y = nas_bias_y; packet->nas_bias_z = nas_bias_z; - packet->estimated_thrust = estimated_thrust; - packet->vbat = vbat; + packet->battery_voltage = battery_voltage; + packet->current_consumption = current_consumption; packet->temperature = temperature; packet->ada_state = ada_state; packet->fmm_state = fmm_state; packet->dpl_state = dpl_state; packet->abk_state = abk_state; packet->nas_state = nas_state; + packet->mea_state = mea_state; packet->gps_fix = gps_fix; packet->pin_launch = pin_launch; packet->pin_nosecone = pin_nosecone; @@ -888,7 +888,7 @@ static inline uint64_t mavlink_msg_rocket_flight_tm_get_timestamp(const mavlink_ */ static inline uint8_t mavlink_msg_rocket_flight_tm_get_ada_state(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 160); + return _MAV_RETURN_uint8_t(msg, 156); } /** @@ -898,7 +898,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_ada_state(const mavlink_m */ static inline uint8_t mavlink_msg_rocket_flight_tm_get_fmm_state(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 161); + return _MAV_RETURN_uint8_t(msg, 157); } /** @@ -908,7 +908,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_fmm_state(const mavlink_m */ static inline uint8_t mavlink_msg_rocket_flight_tm_get_dpl_state(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 162); + return _MAV_RETURN_uint8_t(msg, 158); } /** @@ -918,7 +918,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_dpl_state(const mavlink_m */ static inline uint8_t mavlink_msg_rocket_flight_tm_get_abk_state(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 163); + return _MAV_RETURN_uint8_t(msg, 159); } /** @@ -928,7 +928,17 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_abk_state(const mavlink_m */ static inline uint8_t mavlink_msg_rocket_flight_tm_get_nas_state(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 164); + return _MAV_RETURN_uint8_t(msg, 160); +} + +/** + * @brief Get field mea_state from rocket_flight_tm message + * + * @return MEA Controller State + */ +static inline uint8_t mavlink_msg_rocket_flight_tm_get_mea_state(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 161); } /** @@ -1001,6 +1011,16 @@ static inline float mavlink_msg_rocket_flight_tm_get_ada_vert_speed(const mavlin return _MAV_RETURN_float(msg, 32); } +/** + * @brief Get field mea_mass from rocket_flight_tm message + * + * @return [kg] Mass estimated by MEA + */ +static inline float mavlink_msg_rocket_flight_tm_get_mea_mass(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + /** * @brief Get field acc_x from rocket_flight_tm message * @@ -1008,7 +1028,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_ada_vert_speed(const mavlin */ static inline float mavlink_msg_rocket_flight_tm_get_acc_x(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 36); + return _MAV_RETURN_float(msg, 40); } /** @@ -1018,7 +1038,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_acc_x(const mavlink_message */ static inline float mavlink_msg_rocket_flight_tm_get_acc_y(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 40); + return _MAV_RETURN_float(msg, 44); } /** @@ -1028,7 +1048,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_acc_y(const mavlink_message */ static inline float mavlink_msg_rocket_flight_tm_get_acc_z(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 44); + return _MAV_RETURN_float(msg, 48); } /** @@ -1038,7 +1058,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_acc_z(const mavlink_message */ static inline float mavlink_msg_rocket_flight_tm_get_gyro_x(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 48); + return _MAV_RETURN_float(msg, 52); } /** @@ -1048,7 +1068,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_gyro_x(const mavlink_messag */ static inline float mavlink_msg_rocket_flight_tm_get_gyro_y(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 52); + return _MAV_RETURN_float(msg, 56); } /** @@ -1058,7 +1078,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_gyro_y(const mavlink_messag */ static inline float mavlink_msg_rocket_flight_tm_get_gyro_z(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 56); + return _MAV_RETURN_float(msg, 60); } /** @@ -1068,7 +1088,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_gyro_z(const mavlink_messag */ static inline float mavlink_msg_rocket_flight_tm_get_mag_x(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 60); + return _MAV_RETURN_float(msg, 64); } /** @@ -1078,7 +1098,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_mag_x(const mavlink_message */ static inline float mavlink_msg_rocket_flight_tm_get_mag_y(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 64); + return _MAV_RETURN_float(msg, 68); } /** @@ -1088,7 +1108,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_mag_y(const mavlink_message */ static inline float mavlink_msg_rocket_flight_tm_get_mag_z(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 68); + return _MAV_RETURN_float(msg, 72); } /** @@ -1098,7 +1118,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_mag_z(const mavlink_message */ static inline uint8_t mavlink_msg_rocket_flight_tm_get_gps_fix(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 165); + return _MAV_RETURN_uint8_t(msg, 162); } /** @@ -1108,7 +1128,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_gps_fix(const mavlink_mes */ static inline float mavlink_msg_rocket_flight_tm_get_gps_lat(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 72); + return _MAV_RETURN_float(msg, 76); } /** @@ -1118,7 +1138,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_gps_lat(const mavlink_messa */ static inline float mavlink_msg_rocket_flight_tm_get_gps_lon(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 76); + return _MAV_RETURN_float(msg, 80); } /** @@ -1128,7 +1148,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_gps_lon(const mavlink_messa */ static inline float mavlink_msg_rocket_flight_tm_get_gps_alt(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 80); + return _MAV_RETURN_float(msg, 84); } /** @@ -1137,30 +1157,10 @@ static inline float mavlink_msg_rocket_flight_tm_get_gps_alt(const mavlink_messa * @return [deg] Air Brakes angle */ static inline float mavlink_msg_rocket_flight_tm_get_abk_angle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 84); -} - -/** - * @brief Get field abk_estimated_cd from rocket_flight_tm message - * - * @return Estimated drag coefficient - */ -static inline float mavlink_msg_rocket_flight_tm_get_abk_estimated_cd(const mavlink_message_t* msg) { return _MAV_RETURN_float(msg, 88); } -/** - * @brief Get field parachute_load from rocket_flight_tm message - * - * @return Parachute load cell value - */ -static inline float mavlink_msg_rocket_flight_tm_get_parachute_load(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 92); -} - /** * @brief Get field nas_n from rocket_flight_tm message * @@ -1168,7 +1168,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_parachute_load(const mavlin */ static inline float mavlink_msg_rocket_flight_tm_get_nas_n(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 96); + return _MAV_RETURN_float(msg, 92); } /** @@ -1178,7 +1178,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_n(const mavlink_message */ static inline float mavlink_msg_rocket_flight_tm_get_nas_e(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 100); + return _MAV_RETURN_float(msg, 96); } /** @@ -1188,7 +1188,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_e(const mavlink_message */ static inline float mavlink_msg_rocket_flight_tm_get_nas_d(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 104); + return _MAV_RETURN_float(msg, 100); } /** @@ -1198,7 +1198,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_d(const mavlink_message */ static inline float mavlink_msg_rocket_flight_tm_get_nas_vn(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 108); + return _MAV_RETURN_float(msg, 104); } /** @@ -1208,7 +1208,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_vn(const mavlink_messag */ static inline float mavlink_msg_rocket_flight_tm_get_nas_ve(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 112); + return _MAV_RETURN_float(msg, 108); } /** @@ -1218,7 +1218,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_ve(const mavlink_messag */ static inline float mavlink_msg_rocket_flight_tm_get_nas_vd(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 116); + return _MAV_RETURN_float(msg, 112); } /** @@ -1228,7 +1228,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_vd(const mavlink_messag */ static inline float mavlink_msg_rocket_flight_tm_get_nas_qx(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 120); + return _MAV_RETURN_float(msg, 116); } /** @@ -1238,7 +1238,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_qx(const mavlink_messag */ static inline float mavlink_msg_rocket_flight_tm_get_nas_qy(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 124); + return _MAV_RETURN_float(msg, 120); } /** @@ -1248,7 +1248,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_qy(const mavlink_messag */ static inline float mavlink_msg_rocket_flight_tm_get_nas_qz(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 128); + return _MAV_RETURN_float(msg, 124); } /** @@ -1258,7 +1258,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_qz(const mavlink_messag */ static inline float mavlink_msg_rocket_flight_tm_get_nas_qw(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 132); + return _MAV_RETURN_float(msg, 128); } /** @@ -1268,7 +1268,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_qw(const mavlink_messag */ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_x(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 136); + return _MAV_RETURN_float(msg, 132); } /** @@ -1278,7 +1278,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_x(const mavlink_me */ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_y(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 140); + return _MAV_RETURN_float(msg, 136); } /** @@ -1288,7 +1288,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_y(const mavlink_me */ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_z(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 144); + return _MAV_RETURN_float(msg, 140); } /** @@ -1298,7 +1298,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_z(const mavlink_me */ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_launch(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 166); + return _MAV_RETURN_uint8_t(msg, 163); } /** @@ -1308,7 +1308,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_launch(const mavlink_ */ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_nosecone(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 167); + return _MAV_RETURN_uint8_t(msg, 164); } /** @@ -1318,7 +1318,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_nosecone(const mavlin */ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_expulsion(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 168); + return _MAV_RETURN_uint8_t(msg, 165); } /** @@ -1328,27 +1328,27 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_expulsion(const mavli */ static inline uint8_t mavlink_msg_rocket_flight_tm_get_cutter_presence(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 169); + return _MAV_RETURN_uint8_t(msg, 166); } /** - * @brief Get field estimated_thrust from rocket_flight_tm message + * @brief Get field battery_voltage from rocket_flight_tm message * - * @return Estimated thrust from automatic shutdown algorithm + * @return [V] Battery voltage */ -static inline float mavlink_msg_rocket_flight_tm_get_estimated_thrust(const mavlink_message_t* msg) +static inline float mavlink_msg_rocket_flight_tm_get_battery_voltage(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 148); + return _MAV_RETURN_float(msg, 144); } /** - * @brief Get field vbat from rocket_flight_tm message + * @brief Get field current_consumption from rocket_flight_tm message * - * @return [V] Battery voltage + * @return [A] Battery current */ -static inline float mavlink_msg_rocket_flight_tm_get_vbat(const mavlink_message_t* msg) +static inline float mavlink_msg_rocket_flight_tm_get_current_consumption(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 152); + return _MAV_RETURN_float(msg, 148); } /** @@ -1358,7 +1358,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_vbat(const mavlink_message_ */ static inline float mavlink_msg_rocket_flight_tm_get_temperature(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 156); + return _MAV_RETURN_float(msg, 152); } /** @@ -1368,7 +1368,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_temperature(const mavlink_m */ static inline int8_t mavlink_msg_rocket_flight_tm_get_logger_error(const mavlink_message_t* msg) { - return _MAV_RETURN_int8_t(msg, 170); + return _MAV_RETURN_int8_t(msg, 167); } /** @@ -1388,6 +1388,7 @@ static inline void mavlink_msg_rocket_flight_tm_decode(const mavlink_message_t* rocket_flight_tm->airspeed_pitot = mavlink_msg_rocket_flight_tm_get_airspeed_pitot(msg); rocket_flight_tm->altitude_agl = mavlink_msg_rocket_flight_tm_get_altitude_agl(msg); rocket_flight_tm->ada_vert_speed = mavlink_msg_rocket_flight_tm_get_ada_vert_speed(msg); + rocket_flight_tm->mea_mass = mavlink_msg_rocket_flight_tm_get_mea_mass(msg); rocket_flight_tm->acc_x = mavlink_msg_rocket_flight_tm_get_acc_x(msg); rocket_flight_tm->acc_y = mavlink_msg_rocket_flight_tm_get_acc_y(msg); rocket_flight_tm->acc_z = mavlink_msg_rocket_flight_tm_get_acc_z(msg); @@ -1401,8 +1402,6 @@ static inline void mavlink_msg_rocket_flight_tm_decode(const mavlink_message_t* rocket_flight_tm->gps_lon = mavlink_msg_rocket_flight_tm_get_gps_lon(msg); rocket_flight_tm->gps_alt = mavlink_msg_rocket_flight_tm_get_gps_alt(msg); rocket_flight_tm->abk_angle = mavlink_msg_rocket_flight_tm_get_abk_angle(msg); - rocket_flight_tm->abk_estimated_cd = mavlink_msg_rocket_flight_tm_get_abk_estimated_cd(msg); - rocket_flight_tm->parachute_load = mavlink_msg_rocket_flight_tm_get_parachute_load(msg); rocket_flight_tm->nas_n = mavlink_msg_rocket_flight_tm_get_nas_n(msg); rocket_flight_tm->nas_e = mavlink_msg_rocket_flight_tm_get_nas_e(msg); rocket_flight_tm->nas_d = mavlink_msg_rocket_flight_tm_get_nas_d(msg); @@ -1416,14 +1415,15 @@ static inline void mavlink_msg_rocket_flight_tm_decode(const mavlink_message_t* rocket_flight_tm->nas_bias_x = mavlink_msg_rocket_flight_tm_get_nas_bias_x(msg); rocket_flight_tm->nas_bias_y = mavlink_msg_rocket_flight_tm_get_nas_bias_y(msg); rocket_flight_tm->nas_bias_z = mavlink_msg_rocket_flight_tm_get_nas_bias_z(msg); - rocket_flight_tm->estimated_thrust = mavlink_msg_rocket_flight_tm_get_estimated_thrust(msg); - rocket_flight_tm->vbat = mavlink_msg_rocket_flight_tm_get_vbat(msg); + rocket_flight_tm->battery_voltage = mavlink_msg_rocket_flight_tm_get_battery_voltage(msg); + rocket_flight_tm->current_consumption = mavlink_msg_rocket_flight_tm_get_current_consumption(msg); rocket_flight_tm->temperature = mavlink_msg_rocket_flight_tm_get_temperature(msg); rocket_flight_tm->ada_state = mavlink_msg_rocket_flight_tm_get_ada_state(msg); rocket_flight_tm->fmm_state = mavlink_msg_rocket_flight_tm_get_fmm_state(msg); rocket_flight_tm->dpl_state = mavlink_msg_rocket_flight_tm_get_dpl_state(msg); rocket_flight_tm->abk_state = mavlink_msg_rocket_flight_tm_get_abk_state(msg); rocket_flight_tm->nas_state = mavlink_msg_rocket_flight_tm_get_nas_state(msg); + rocket_flight_tm->mea_state = mavlink_msg_rocket_flight_tm_get_mea_state(msg); rocket_flight_tm->gps_fix = mavlink_msg_rocket_flight_tm_get_gps_fix(msg); rocket_flight_tm->pin_launch = mavlink_msg_rocket_flight_tm_get_pin_launch(msg); rocket_flight_tm->pin_nosecone = mavlink_msg_rocket_flight_tm_get_pin_nosecone(msg); diff --git a/mavlink_lib/gemini/testsuite.h b/mavlink_lib/gemini/testsuite.h index 1e8930d..f6c6fed 100644 --- a/mavlink_lib/gemini/testsuite.h +++ b/mavlink_lib/gemini/testsuite.h @@ -2655,6 +2655,71 @@ static void mavlink_test_nas_tm(uint8_t system_id, uint8_t component_id, mavlink #endif } +static void mavlink_test_mea_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ +#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 + mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0); + if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MEA_TM >= 256) { + return; + } +#endif + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_mea_tm_t packet_in = { + 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,89 + }; + mavlink_mea_tm_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.timestamp = packet_in.timestamp; + packet1.kalman_x0 = packet_in.kalman_x0; + packet1.kalman_x1 = packet_in.kalman_x1; + packet1.kalman_x2 = packet_in.kalman_x2; + packet1.mass = packet_in.mass; + packet1.corrected_pressure = packet_in.corrected_pressure; + packet1.state = packet_in.state; + + +#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 + if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { + // cope with extensions + memset(MAVLINK_MSG_ID_MEA_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MEA_TM_MIN_LEN); + } +#endif + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_mea_tm_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_mea_tm_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_mea_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.mass , packet1.corrected_pressure ); + mavlink_msg_mea_tm_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_mea_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.mass , packet1.corrected_pressure ); + mavlink_msg_mea_tm_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) { + comm_send_ch(MAVLINK_COMM_0, buffer[i]); + } + mavlink_msg_mea_tm_decode(last_msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_mea_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.mass , packet1.corrected_pressure ); + mavlink_msg_mea_tm_decode(last_msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + +#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO + MAVLINK_ASSERT(mavlink_get_message_info_by_name("MEA_TM") != NULL); + MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_MEA_TM) != NULL); +#endif +} + static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) { #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 @@ -2667,7 +2732,7 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_rocket_flight_tm_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,1109.0,229,40,107,174,241,52,119,186,253,64,131 + 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,217,28,95,162,229,40,107,174,241,52,119,186 }; mavlink_rocket_flight_tm_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2679,6 +2744,7 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i packet1.airspeed_pitot = packet_in.airspeed_pitot; packet1.altitude_agl = packet_in.altitude_agl; packet1.ada_vert_speed = packet_in.ada_vert_speed; + packet1.mea_mass = packet_in.mea_mass; packet1.acc_x = packet_in.acc_x; packet1.acc_y = packet_in.acc_y; packet1.acc_z = packet_in.acc_z; @@ -2692,8 +2758,6 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i packet1.gps_lon = packet_in.gps_lon; packet1.gps_alt = packet_in.gps_alt; packet1.abk_angle = packet_in.abk_angle; - packet1.abk_estimated_cd = packet_in.abk_estimated_cd; - packet1.parachute_load = packet_in.parachute_load; packet1.nas_n = packet_in.nas_n; packet1.nas_e = packet_in.nas_e; packet1.nas_d = packet_in.nas_d; @@ -2707,14 +2771,15 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i packet1.nas_bias_x = packet_in.nas_bias_x; packet1.nas_bias_y = packet_in.nas_bias_y; packet1.nas_bias_z = packet_in.nas_bias_z; - packet1.estimated_thrust = packet_in.estimated_thrust; - packet1.vbat = packet_in.vbat; + packet1.battery_voltage = packet_in.battery_voltage; + packet1.current_consumption = packet_in.current_consumption; packet1.temperature = packet_in.temperature; packet1.ada_state = packet_in.ada_state; packet1.fmm_state = packet_in.fmm_state; packet1.dpl_state = packet_in.dpl_state; packet1.abk_state = packet_in.abk_state; packet1.nas_state = packet_in.nas_state; + packet1.mea_state = packet_in.mea_state; packet1.gps_fix = packet_in.gps_fix; packet1.pin_launch = packet_in.pin_launch; packet1.pin_nosecone = packet_in.pin_nosecone; @@ -2735,12 +2800,12 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rocket_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.abk_estimated_cd , packet1.parachute_load , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.estimated_thrust , packet1.vbat , packet1.temperature , packet1.logger_error ); + mavlink_msg_rocket_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error ); mavlink_msg_rocket_flight_tm_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.abk_estimated_cd , packet1.parachute_load , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.estimated_thrust , packet1.vbat , packet1.temperature , packet1.logger_error ); + mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error ); mavlink_msg_rocket_flight_tm_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -2753,7 +2818,7 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rocket_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.abk_estimated_cd , packet1.parachute_load , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.estimated_thrust , packet1.vbat , packet1.temperature , packet1.logger_error ); + mavlink_msg_rocket_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error ); mavlink_msg_rocket_flight_tm_decode(last_msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -2775,7 +2840,7 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_ uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_payload_flight_tm_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,205,16,83,150,217,28 + 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,217,28,95,162,229,40 }; mavlink_payload_flight_tm_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -2813,7 +2878,8 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_ packet1.nas_bias_z = packet_in.nas_bias_z; packet1.wes_n = packet_in.wes_n; packet1.wes_e = packet_in.wes_e; - packet1.vbat = packet_in.vbat; + packet1.battery_voltage = packet_in.battery_voltage; + packet1.current_consumption = packet_in.current_consumption; packet1.vsupply_5v = packet_in.vsupply_5v; packet1.temperature = packet_in.temperature; packet1.fmm_state = packet_in.fmm_state; @@ -2836,12 +2902,12 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_payload_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.logger_error ); + mavlink_msg_payload_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.current_consumption , packet1.vsupply_5v , packet1.temperature , packet1.logger_error ); mavlink_msg_payload_flight_tm_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.logger_error ); + mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.current_consumption , packet1.vsupply_5v , packet1.temperature , packet1.logger_error ); mavlink_msg_payload_flight_tm_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -2854,7 +2920,7 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_payload_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.logger_error ); + mavlink_msg_payload_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.current_consumption , packet1.vsupply_5v , packet1.temperature , packet1.logger_error ); mavlink_msg_payload_flight_tm_decode(last_msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -3100,7 +3166,7 @@ static void mavlink_test_motor_tm(uint8_t system_id, uint8_t component_id, mavli uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_motor_tm_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,77,144 + 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,101,168 }; mavlink_motor_tm_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3109,6 +3175,8 @@ static void mavlink_test_motor_tm(uint8_t system_id, uint8_t component_id, mavli packet1.bottom_tank_pressure = packet_in.bottom_tank_pressure; packet1.combustion_chamber_pressure = packet_in.combustion_chamber_pressure; packet1.tank_temperature = packet_in.tank_temperature; + packet1.battery_voltage = packet_in.battery_voltage; + packet1.current_consumption = packet_in.current_consumption; packet1.floating_level = packet_in.floating_level; packet1.main_valve_state = packet_in.main_valve_state; @@ -3125,12 +3193,12 @@ static void mavlink_test_motor_tm(uint8_t system_id, uint8_t component_id, mavli MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_motor_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state ); + mavlink_msg_motor_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state , packet1.battery_voltage , packet1.current_consumption ); mavlink_msg_motor_tm_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_motor_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state ); + mavlink_msg_motor_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state , packet1.battery_voltage , packet1.current_consumption ); mavlink_msg_motor_tm_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -3143,7 +3211,7 @@ static void mavlink_test_motor_tm(uint8_t system_id, uint8_t component_id, mavli MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_motor_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state ); + mavlink_msg_motor_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state , packet1.battery_voltage , packet1.current_consumption ); mavlink_msg_motor_tm_decode(last_msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -3197,6 +3265,7 @@ static void mavlink_test_gemini(uint8_t system_id, uint8_t component_id, mavlink mavlink_test_task_stats_tm(system_id, component_id, last_msg); mavlink_test_ada_tm(system_id, component_id, last_msg); mavlink_test_nas_tm(system_id, component_id, last_msg); + mavlink_test_mea_tm(system_id, component_id, last_msg); mavlink_test_rocket_flight_tm(system_id, component_id, last_msg); mavlink_test_payload_flight_tm(system_id, component_id, last_msg); mavlink_test_rocket_stats_tm(system_id, component_id, last_msg); diff --git a/mavlink_lib/gemini/version.h b/mavlink_lib/gemini/version.h index b22a23f..5452bc6 100644 --- a/mavlink_lib/gemini/version.h +++ b/mavlink_lib/gemini/version.h @@ -7,8 +7,8 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Sun Aug 27 2023" +#define MAVLINK_BUILD_DATE "Mon Aug 28 2023" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" -#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 171 +#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 168 #endif // MAVLINK_VERSION_H diff --git a/message_definitions/gemini.xml b/message_definitions/gemini.xml index 1ee1025..cb2617c 100644 --- a/message_definitions/gemini.xml +++ b/message_definitions/gemini.xml @@ -2,6 +2,12 @@ <mavlink> <version>1</version> <enums> + <enum name="SysIDs"> + <description>Enum that lists all the system IDs of the various devices</description> + <entry name="MAIN" value="1"></entry> + <entry name="PAYLOAD" value="2"></entry> + <entry name="RIG" value="3"></entry> + </enum> <enum name="SystemTMList"> <description>Enum list for all the telemetries that can be requested</description> <entry name="MAV_SYS_ID" value="1"> @@ -28,27 +34,27 @@ <entry name="MAV_NAS_ID" value="8"> <description>NavigationSystem data</description> </entry> - <entry name="MAV_CAN_ID" value="9"> + <entry name="MAV_MEA_ID" value="9"> + <description>MEA Status</description> + </entry> + <entry name="MAV_CAN_ID" value="10"> <description>Canbus stats</description> </entry> - <entry name="MAV_FLIGHT_ID" value="10"> + <entry name="MAV_FLIGHT_ID" value="11"> <description>Flight telemetry</description> </entry> - <entry name="MAV_STATS_ID" value="11"> + <entry name="MAV_STATS_ID" value="12"> <description>Satistics telemetry</description> </entry> - <entry name="MAV_SENSORS_STATE_ID" value="12"> + <entry name="MAV_SENSORS_STATE_ID" value="13"> <description>Sensors init state telemetry</description> </entry> - <entry name="MAV_GSE_ID" value="13"> + <entry name="MAV_GSE_ID" value="14"> <description>Ground Segnement Equipment</description> </entry> - <entry name="MAV_MOTOR_ID" value="14"> + <entry name="MAV_MOTOR_ID" value="15"> <description>Rocket Motor data</description> </entry> - <entry name="MAV_TARS_ID" value="15"> - <description>TARS data</description> - </entry> </enum> <enum name="SensorsTMList"> <description>Enum list of all sensors telemetries that can be requested</description> @@ -541,6 +547,16 @@ <field name="ref_latitude" type="float" units="deg">Calibration latitude</field> <field name="ref_longitude" type="float" units="deg">Calibration longitude</field> </message> + <message id="207" name="MEA_TM"> + <description>Mass Estimation Algorithm status telemetry</description> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> + <field name="state" type="uint8_t">MEA current state</field> + <field name="kalman_x0" type="float">Kalman state variable 0 (corrected pressure)</field> + <field name="kalman_x1" type="float">Kalman state variable 1 </field> + <field name="kalman_x2" type="float">Kalman state variable 2 (mass)</field> + <field name="mass" type="float" units="kg">Mass estimated</field> + <field name="corrected_pressure" type="float" units="kg">Corrected pressure</field> + </message> <message id="208" name="ROCKET_FLIGHT_TM"> <description>High Rate Telemetry</description> <field name="timestamp" type="uint64_t" units="us">Timestamp in microseconds</field> @@ -549,6 +565,7 @@ <field name="dpl_state" type="uint8_t">Deployment Controller State</field> <field name="abk_state" type="uint8_t">Airbrake FSM state</field> <field name="nas_state" type="uint8_t">Navigation System FSM State</field> + <field name="mea_state" type="uint8_t">MEA Controller State</field> <field name="pressure_ada" type="float" units="Pa">Atmospheric pressure estimated by ADA</field> <field name="pressure_digi" type="float" units="Pa">Pressure from digital sensor</field> <field name="pressure_static" type="float" units="Pa">Pressure from static port</field> @@ -556,6 +573,7 @@ <field name="airspeed_pitot" type="float" units="m/s">Pitot airspeed</field> <field name="altitude_agl" type="float" units="m">Altitude above ground level</field> <field name="ada_vert_speed" type="float" units="m/s">Vertical speed estimated by ADA</field> + <field name="mea_mass" type="float" units="kg">Mass estimated by MEA</field> <field name="acc_x" type="float" units="m/s^2">Acceleration on X axis (body)</field> <field name="acc_y" type="float" units="m/s^2">Acceleration on Y axis (body)</field> <field name="acc_z" type="float" units="m/s^2">Acceleration on Z axis (body)</field> @@ -570,8 +588,6 @@ <field name="gps_lon" type="float" units="deg">Longitude</field> <field name="gps_alt" type="float" units="m">GPS Altitude</field> <field name="abk_angle" type="float" units="deg">Air Brakes angle</field> - <field name="abk_estimated_cd" type="float">Estimated drag coefficient</field> - <field name="parachute_load" type="float">Parachute load cell value</field> <field name="nas_n" type="float" units="deg">Navigation system estimated noth position</field> <field name="nas_e" type="float" units="deg">Navigation system estimated east position</field> <field name="nas_d" type="float" units="m">Navigation system estimated down position</field> @@ -589,8 +605,8 @@ <field name="pin_nosecone" type="uint8_t">Nosecone pin status (1 = connected, 0 = disconnected)</field> <field name="pin_expulsion" type="uint8_t">Servo sensor status (1 = actuated, 0 = idle)</field> <field name="cutter_presence" type="uint8_t">Cutter presence status (1 = present, 0 = missing)</field> - <field name="estimated_thrust" type="float">Estimated thrust from automatic shutdown algorithm</field> - <field name="vbat" type="float" units="V">Battery voltage</field> + <field name="battery_voltage" type="float" units="V">Battery voltage</field> + <field name="current_consumption" type="float" units="A">Battery current</field> <field name="temperature" type="float" units="degC">Temperature</field> <field name="logger_error" type="int8_t">Logger error (0 = no error, -1 otherwise)</field> </message> @@ -635,7 +651,8 @@ <field name="wes_n" type="float" units="m/s">Wind estimated north velocity</field> <field name="wes_e" type="float" units="m/s">Wind estimated east velocity</field> <field name="pin_nosecone" type="uint8_t">Nosecone pin status (1 = connected, 0 = disconnected)</field> - <field name="vbat" type="float" units="V">Battery voltage</field> + <field name="battery_voltage" type="float" units="V">Battery voltage</field> + <field name="current_consumption" type="float" units="A">Battery current</field> <field name="vsupply_5v" type="float" units="V">Power supply 5V</field> <field name="temperature" type="float" units="degC">Temperature</field> <field name="logger_error" type="int8_t">Logger error (0 = no error)</field> @@ -707,7 +724,9 @@ <field name="combustion_chamber_pressure" type="float" units="Bar">Pressure inside the combustion chamber used for automatic shutdown</field> <field name="floating_level" type="uint8_t">Floating level in tank</field> <field name="tank_temperature" type="float">Tank temperature</field> - <field name="main_valve_state" type="uint8_t"> 1 If the main valve is open </field> + <field name="main_valve_state" type="uint8_t">1 If the main valve is open </field> + <field name="battery_voltage" type="float" units="V">Battery voltage</field> + <field name="current_consumption" type="float" units="A">Current drained from the battery</field> </message> </messages> </mavlink> -- GitLab