diff --git a/mavlink_lib.py b/mavlink_lib.py
index ec376da70577e23a70d13b34558bdd3becb0ad52..01285d232d1c367201367c667665f1165c16939e 100644
--- a/mavlink_lib.py
+++ b/mavlink_lib.py
@@ -283,98 +283,104 @@ enums['SysIDs'][5] = EnumEntry('SysIDs_ENUM_END', '''''')
 enums['SystemTMList'] = {}
 MAV_SYS_ID = 1 # State of init results about system hardware/software components
 enums['SystemTMList'][1] = EnumEntry('MAV_SYS_ID', '''State of init results about system hardware/software components''')
-MAV_FSM_ID = 2 # States of all On-Board FSMs
-enums['SystemTMList'][2] = EnumEntry('MAV_FSM_ID', '''States of all On-Board FSMs''')
-MAV_PIN_OBS_ID = 3 # Pin observer data
-enums['SystemTMList'][3] = EnumEntry('MAV_PIN_OBS_ID', '''Pin observer data''')
-MAV_LOGGER_ID = 4 # SD Logger stats
-enums['SystemTMList'][4] = EnumEntry('MAV_LOGGER_ID', '''SD Logger stats''')
-MAV_MAVLINK_STATS = 5 # Mavlink driver stats
-enums['SystemTMList'][5] = EnumEntry('MAV_MAVLINK_STATS', '''Mavlink driver stats''')
-MAV_TASK_STATS_ID = 6 # Task scheduler statistics answer: n mavlink messages where n is the
+MAV_PIN_OBS_ID = 2 # Pin observer data
+enums['SystemTMList'][2] = EnumEntry('MAV_PIN_OBS_ID', '''Pin observer data''')
+MAV_LOGGER_ID = 3 # SD Logger stats
+enums['SystemTMList'][3] = EnumEntry('MAV_LOGGER_ID', '''SD Logger stats''')
+MAV_MAVLINK_STATS_ID = 4 # Mavlink driver stats
+enums['SystemTMList'][4] = EnumEntry('MAV_MAVLINK_STATS_ID', '''Mavlink driver stats''')
+MAV_TASK_STATS_ID = 5 # Task scheduler statistics answer: n mavlink messages where n is the
                         # number of tasks
-enums['SystemTMList'][6] = EnumEntry('MAV_TASK_STATS_ID', '''Task scheduler statistics answer: n mavlink messages where n is the number of tasks''')
-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_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''')
-MAV_REGISTRY_ID = 22 # Command to fetch all registry keys
-enums['SystemTMList'][22] = EnumEntry('MAV_REGISTRY_ID', '''Command to fetch all registry keys''')
-SystemTMList_ENUM_END = 23 # 
-enums['SystemTMList'][23] = EnumEntry('SystemTMList_ENUM_END', '''''')
+enums['SystemTMList'][5] = EnumEntry('MAV_TASK_STATS_ID', '''Task scheduler statistics answer: n mavlink messages where n is the number of tasks''')
+MAV_ADA_ID = 6 # ADA Status
+enums['SystemTMList'][6] = EnumEntry('MAV_ADA_ID', '''ADA Status''')
+MAV_NAS_ID = 7 # NavigationSystem data
+enums['SystemTMList'][7] = EnumEntry('MAV_NAS_ID', '''NavigationSystem data''')
+MAV_MEA_ID = 8 # MEA Status
+enums['SystemTMList'][8] = EnumEntry('MAV_MEA_ID', '''MEA Status''')
+MAV_CAN_STATS_ID = 9 # Canbus stats
+enums['SystemTMList'][9] = EnumEntry('MAV_CAN_STATS_ID', '''Canbus stats''')
+MAV_FLIGHT_ID = 10 # Flight telemetry
+enums['SystemTMList'][10] = EnumEntry('MAV_FLIGHT_ID', '''Flight telemetry''')
+MAV_STATS_ID = 11 # Satistics telemetry
+enums['SystemTMList'][11] = EnumEntry('MAV_STATS_ID', '''Satistics telemetry''')
+MAV_SENSORS_STATE_ID = 12 # Sensors init state telemetry
+enums['SystemTMList'][12] = EnumEntry('MAV_SENSORS_STATE_ID', '''Sensors init state telemetry''')
+MAV_GSE_ID = 13 # Ground Segnement Equipment
+enums['SystemTMList'][13] = EnumEntry('MAV_GSE_ID', '''Ground Segnement Equipment''')
+MAV_MOTOR_ID = 14 # Rocket Motor data
+enums['SystemTMList'][14] = EnumEntry('MAV_MOTOR_ID', '''Rocket Motor data''')
+MAV_REGISTRY_ID = 15 # Command to fetch all registry keys
+enums['SystemTMList'][15] = EnumEntry('MAV_REGISTRY_ID', '''Command to fetch all registry keys''')
+SystemTMList_ENUM_END = 16 # 
+enums['SystemTMList'][16] = EnumEntry('SystemTMList_ENUM_END', '''''')
 
 # SensorsTMList
 enums['SensorsTMList'] = {}
-MAV_GPS_ID = 1 # GPS data
-enums['SensorsTMList'][1] = EnumEntry('MAV_GPS_ID', '''GPS data''')
-MAV_BMX160_ID = 2 # BMX160 IMU data
-enums['SensorsTMList'][2] = EnumEntry('MAV_BMX160_ID', '''BMX160 IMU data''')
-MAV_VN100_ID = 3 # VN100 IMU data
-enums['SensorsTMList'][3] = EnumEntry('MAV_VN100_ID', '''VN100 IMU data''')
-MAV_MPU9250_ID = 4 # MPU9250 IMU data
-enums['SensorsTMList'][4] = EnumEntry('MAV_MPU9250_ID', '''MPU9250 IMU data''')
-MAV_ADS_ID = 5 # ADS 8 channel ADC data
-enums['SensorsTMList'][5] = EnumEntry('MAV_ADS_ID', '''ADS 8 channel ADC data''')
-MAV_MS5803_ID = 6 # MS5803 barometer data
-enums['SensorsTMList'][6] = EnumEntry('MAV_MS5803_ID', '''MS5803 barometer data''')
-MAV_BME280_ID = 7 # BME280 barometer data
-enums['SensorsTMList'][7] = EnumEntry('MAV_BME280_ID', '''BME280 barometer data''')
-MAV_CURRENT_SENSE_ID = 8 # Electrical current sensors data
-enums['SensorsTMList'][8] = EnumEntry('MAV_CURRENT_SENSE_ID', '''Electrical current sensors data''')
-MAV_LIS3MDL_ID = 9 # LIS3MDL compass data
-enums['SensorsTMList'][9] = EnumEntry('MAV_LIS3MDL_ID', '''LIS3MDL compass data''')
-MAV_DPL_PRESS_ID = 10 # Deployment pressure data
-enums['SensorsTMList'][10] = EnumEntry('MAV_DPL_PRESS_ID', '''Deployment pressure data''')
-MAV_STATIC_PRESS_ID = 11 # Static pressure data
-enums['SensorsTMList'][11] = EnumEntry('MAV_STATIC_PRESS_ID', '''Static pressure data''')
-MAV_PITOT_PRESS_ID = 12 # Pitot pressure data
-enums['SensorsTMList'][12] = EnumEntry('MAV_PITOT_PRESS_ID', '''Pitot pressure data''')
-MAV_BATTERY_VOLTAGE_ID = 13 # Battery voltage data
-enums['SensorsTMList'][13] = EnumEntry('MAV_BATTERY_VOLTAGE_ID', '''Battery voltage data''')
-MAV_LOAD_CELL_ID = 14 # Load cell data
-enums['SensorsTMList'][14] = EnumEntry('MAV_LOAD_CELL_ID', '''Load cell data''')
-MAV_FILLING_PRESS_ID = 15 # Filling line pressure
-enums['SensorsTMList'][15] = EnumEntry('MAV_FILLING_PRESS_ID', '''Filling line pressure''')
-MAV_TANK_TOP_PRESS_ID = 16 # Top tank pressure
-enums['SensorsTMList'][16] = EnumEntry('MAV_TANK_TOP_PRESS_ID', '''Top tank pressure''')
-MAV_TANK_BOTTOM_PRESS_ID = 17 # Bottom tank pressure
-enums['SensorsTMList'][17] = EnumEntry('MAV_TANK_BOTTOM_PRESS_ID', '''Bottom tank pressure''')
-MAV_TANK_TEMP_ID = 18 # Tank temperature
-enums['SensorsTMList'][18] = EnumEntry('MAV_TANK_TEMP_ID', '''Tank temperature''')
-MAV_COMBUSTION_PRESS_ID = 19 # Combustion chamber pressure
-enums['SensorsTMList'][19] = EnumEntry('MAV_COMBUSTION_PRESS_ID', '''Combustion chamber pressure''')
-MAV_VESSEL_PRESS_ID = 20 # Vessel pressure
-enums['SensorsTMList'][20] = EnumEntry('MAV_VESSEL_PRESS_ID', '''Vessel pressure''')
-MAV_LOAD_CELL_VESSEL_ID = 21 # Vessel tank weight
-enums['SensorsTMList'][21] = EnumEntry('MAV_LOAD_CELL_VESSEL_ID', '''Vessel tank weight''')
-MAV_LOAD_CELL_TANK_ID = 22 # Tank weight
-enums['SensorsTMList'][22] = EnumEntry('MAV_LOAD_CELL_TANK_ID', '''Tank weight''')
-MAV_LIS2MDL_ID = 23 # Magnetometer data
-enums['SensorsTMList'][23] = EnumEntry('MAV_LIS2MDL_ID', '''Magnetometer data''')
-MAV_LPS28DFW_ID = 24 # Pressure sensor data
-enums['SensorsTMList'][24] = EnumEntry('MAV_LPS28DFW_ID', '''Pressure sensor data''')
-MAV_LSM6DSRX_ID = 25 # IMU data
-enums['SensorsTMList'][25] = EnumEntry('MAV_LSM6DSRX_ID', '''IMU data''')
-MAV_H3LIS331DL_ID = 26 # 400G accelerometer
-enums['SensorsTMList'][26] = EnumEntry('MAV_H3LIS331DL_ID', '''400G accelerometer''')
-MAV_LPS22DF_ID = 27 # Pressure sensor data
-enums['SensorsTMList'][27] = EnumEntry('MAV_LPS22DF_ID', '''Pressure sensor data''')
-SensorsTMList_ENUM_END = 28 # 
-enums['SensorsTMList'][28] = EnumEntry('SensorsTMList_ENUM_END', '''''')
+MAV_BMX160_ID = 1 # BMX160 IMU data
+enums['SensorsTMList'][1] = EnumEntry('MAV_BMX160_ID', '''BMX160 IMU data''')
+MAV_VN100_ID = 2 # VN100 IMU data
+enums['SensorsTMList'][2] = EnumEntry('MAV_VN100_ID', '''VN100 IMU data''')
+MAV_MPU9250_ID = 3 # MPU9250 IMU data
+enums['SensorsTMList'][3] = EnumEntry('MAV_MPU9250_ID', '''MPU9250 IMU data''')
+MAV_ADS131M08_ID = 4 # ADS 8 channel ADC data
+enums['SensorsTMList'][4] = EnumEntry('MAV_ADS131M08_ID', '''ADS 8 channel ADC data''')
+MAV_MS5803_ID = 5 # MS5803 barometer data
+enums['SensorsTMList'][5] = EnumEntry('MAV_MS5803_ID', '''MS5803 barometer data''')
+MAV_BME280_ID = 6 # BME280 barometer data
+enums['SensorsTMList'][6] = EnumEntry('MAV_BME280_ID', '''BME280 barometer data''')
+MAV_LIS3MDL_ID = 7 # LIS3MDL compass data
+enums['SensorsTMList'][7] = EnumEntry('MAV_LIS3MDL_ID', '''LIS3MDL compass data''')
+MAV_LIS2MDL_ID = 8 # Magnetometer data
+enums['SensorsTMList'][8] = EnumEntry('MAV_LIS2MDL_ID', '''Magnetometer data''')
+MAV_LPS28DFW_ID = 9 # Pressure sensor data
+enums['SensorsTMList'][9] = EnumEntry('MAV_LPS28DFW_ID', '''Pressure sensor data''')
+MAV_LSM6DSRX_ID = 10 # IMU data
+enums['SensorsTMList'][10] = EnumEntry('MAV_LSM6DSRX_ID', '''IMU data''')
+MAV_H3LIS331DL_ID = 11 # 400G accelerometer
+enums['SensorsTMList'][11] = EnumEntry('MAV_H3LIS331DL_ID', '''400G accelerometer''')
+MAV_LPS22DF_ID = 12 # Pressure sensor data
+enums['SensorsTMList'][12] = EnumEntry('MAV_LPS22DF_ID', '''Pressure sensor data''')
+MAV_GPS_ID = 13 # GPS data
+enums['SensorsTMList'][13] = EnumEntry('MAV_GPS_ID', '''GPS data''')
+MAV_CURRENT_SENSE_ID = 14 # Electrical current sensors data
+enums['SensorsTMList'][14] = EnumEntry('MAV_CURRENT_SENSE_ID', '''Electrical current sensors data''')
+MAV_BATTERY_VOLTAGE_ID = 15 # Battery voltage data
+enums['SensorsTMList'][15] = EnumEntry('MAV_BATTERY_VOLTAGE_ID', '''Battery voltage data''')
+MAV_ROTATED_IMU_ID = 16 # Load cell data
+enums['SensorsTMList'][16] = EnumEntry('MAV_ROTATED_IMU_ID', '''Load cell data''')
+MAV_DPL_PRESS_ID = 17 # Deployment pressure data
+enums['SensorsTMList'][17] = EnumEntry('MAV_DPL_PRESS_ID', '''Deployment pressure data''')
+MAV_STATIC_PRESS_ID = 18 # Static pressure data
+enums['SensorsTMList'][18] = EnumEntry('MAV_STATIC_PRESS_ID', '''Static pressure data''')
+MAV_BACKUP_STATIC_PRESS_ID = 19 # Static pressure data
+enums['SensorsTMList'][19] = EnumEntry('MAV_BACKUP_STATIC_PRESS_ID', '''Static pressure data''')
+MAV_STATIC_PITOT_PRESS_ID = 20 # Pitot pressure data
+enums['SensorsTMList'][20] = EnumEntry('MAV_STATIC_PITOT_PRESS_ID', '''Pitot pressure data''')
+MAV_TOTAL_PITOT_PRESS_ID = 21 # Pitot pressure data
+enums['SensorsTMList'][21] = EnumEntry('MAV_TOTAL_PITOT_PRESS_ID', '''Pitot pressure data''')
+MAV_DYNAMIC_PITOT_PRESS_ID = 22 # Pitot pressure data
+enums['SensorsTMList'][22] = EnumEntry('MAV_DYNAMIC_PITOT_PRESS_ID', '''Pitot pressure data''')
+MAV_LOAD_CELL_ID = 23 # Load cell data
+enums['SensorsTMList'][23] = EnumEntry('MAV_LOAD_CELL_ID', '''Load cell data''')
+MAV_TANK_TOP_PRESS_ID = 24 # Top tank pressure
+enums['SensorsTMList'][24] = EnumEntry('MAV_TANK_TOP_PRESS_ID', '''Top tank pressure''')
+MAV_TANK_BOTTOM_PRESS_ID = 25 # Bottom tank pressure
+enums['SensorsTMList'][25] = EnumEntry('MAV_TANK_BOTTOM_PRESS_ID', '''Bottom tank pressure''')
+MAV_TANK_TEMP_ID = 26 # Tank temperature
+enums['SensorsTMList'][26] = EnumEntry('MAV_TANK_TEMP_ID', '''Tank temperature''')
+MAV_COMBUSTION_PRESS_ID = 27 # Combustion chamber pressure
+enums['SensorsTMList'][27] = EnumEntry('MAV_COMBUSTION_PRESS_ID', '''Combustion chamber pressure''')
+MAV_FILLING_PRESS_ID = 28 # Filling line pressure
+enums['SensorsTMList'][28] = EnumEntry('MAV_FILLING_PRESS_ID', '''Filling line pressure''')
+MAV_VESSEL_PRESS_ID = 29 # Vessel pressure
+enums['SensorsTMList'][29] = EnumEntry('MAV_VESSEL_PRESS_ID', '''Vessel pressure''')
+MAV_LOAD_CELL_VESSEL_ID = 30 # Vessel tank weight
+enums['SensorsTMList'][30] = EnumEntry('MAV_LOAD_CELL_VESSEL_ID', '''Vessel tank weight''')
+MAV_LOAD_CELL_TANK_ID = 31 # Tank weight
+enums['SensorsTMList'][31] = EnumEntry('MAV_LOAD_CELL_TANK_ID', '''Tank weight''')
+SensorsTMList_ENUM_END = 32 # 
+enums['SensorsTMList'][32] = EnumEntry('SensorsTMList_ENUM_END', '''''')
 
 # MavCommandList
 enums['MavCommandList'] = {}
@@ -390,16 +396,16 @@ MAV_CMD_FORCE_INIT = 5 # Command to init the rocket
 enums['MavCommandList'][5] = EnumEntry('MAV_CMD_FORCE_INIT', '''Command to init the rocket''')
 MAV_CMD_FORCE_LAUNCH = 6 # Command to force the launch state on the rocket
 enums['MavCommandList'][6] = EnumEntry('MAV_CMD_FORCE_LAUNCH', '''Command to force the launch state on the rocket''')
-MAV_CMD_FORCE_LANDING = 7 # Command to communicate the end of the mission and close the file
-                        # descriptors in the SD card
-enums['MavCommandList'][7] = EnumEntry('MAV_CMD_FORCE_LANDING', '''Command to communicate the end of the mission and close the file descriptors in the SD card''')
-MAV_CMD_FORCE_APOGEE = 8 # Command to trigger the apogee event
-enums['MavCommandList'][8] = EnumEntry('MAV_CMD_FORCE_APOGEE', '''Command to trigger the apogee event''')
-MAV_CMD_FORCE_EXPULSION = 9 # Command to open the nosecone
-enums['MavCommandList'][9] = EnumEntry('MAV_CMD_FORCE_EXPULSION', '''Command to open the nosecone''')
-MAV_CMD_FORCE_DEPLOYMENT = 10 # Command to activate the thermal cutters and cut the drogue, activating
+MAV_CMD_FORCE_ENGINE_SHUTDOWN = 7 # Command to trigger engine shutdown
+enums['MavCommandList'][7] = EnumEntry('MAV_CMD_FORCE_ENGINE_SHUTDOWN', '''Command to trigger engine shutdown''')
+MAV_CMD_FORCE_EXPULSION = 8 # Command to trigger nosecone expulsion
+enums['MavCommandList'][8] = EnumEntry('MAV_CMD_FORCE_EXPULSION', '''Command to trigger nosecone expulsion''')
+MAV_CMD_FORCE_DEPLOYMENT = 9 # Command to activate the thermal cutters and cut the drogue, activating
                         # both thermal cutters sequentially
-enums['MavCommandList'][10] = EnumEntry('MAV_CMD_FORCE_DEPLOYMENT', '''Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially''')
+enums['MavCommandList'][9] = EnumEntry('MAV_CMD_FORCE_DEPLOYMENT', '''Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially''')
+MAV_CMD_FORCE_LANDING = 10 # Command to communicate the end of the mission and close the file
+                        # descriptors in the SD card
+enums['MavCommandList'][10] = EnumEntry('MAV_CMD_FORCE_LANDING', '''Command to communicate the end of the mission and close the file descriptors in the SD card''')
 MAV_CMD_START_LOGGING = 11 # Command to enable sensor logging
 enums['MavCommandList'][11] = EnumEntry('MAV_CMD_START_LOGGING', '''Command to enable sensor logging''')
 MAV_CMD_STOP_LOGGING = 12 # Command to permanently close the log file
@@ -422,8 +428,10 @@ MAV_CMD_REGISTRY_SAVE = 20 # Command to commit the registry to memory
 enums['MavCommandList'][20] = EnumEntry('MAV_CMD_REGISTRY_SAVE', '''Command to commit the registry to memory''')
 MAV_CMD_REGISTRY_CLEAR = 21 # Command to clear the registry
 enums['MavCommandList'][21] = EnumEntry('MAV_CMD_REGISTRY_CLEAR', '''Command to clear the registry''')
-MavCommandList_ENUM_END = 22 # 
-enums['MavCommandList'][22] = EnumEntry('MavCommandList_ENUM_END', '''''')
+MAV_CMD_ENTER_HIL = 22 # Command to enter HIL mode at next reboot
+enums['MavCommandList'][22] = EnumEntry('MAV_CMD_ENTER_HIL', '''Command to enter HIL mode at next reboot''')
+MavCommandList_ENUM_END = 23 # 
+enums['MavCommandList'][23] = EnumEntry('MavCommandList_ENUM_END', '''''')
 
 # ServosList
 enums['ServosList'] = {}
@@ -459,16 +467,12 @@ enums['StepperList'][3] = EnumEntry('StepperList_ENUM_END', '''''')
 
 # PinsList
 enums['PinsList'] = {}
-LAUNCH_PIN = 1 # 
-enums['PinsList'][1] = EnumEntry('LAUNCH_PIN', '''''')
+RAMP_PIN = 1 # 
+enums['PinsList'][1] = EnumEntry('RAMP_PIN', '''''')
 NOSECONE_PIN = 2 # 
 enums['PinsList'][2] = EnumEntry('NOSECONE_PIN', '''''')
-DEPLOYMENT_PIN = 3 # 
-enums['PinsList'][3] = EnumEntry('DEPLOYMENT_PIN', '''''')
-QUICK_CONNECTOR_PIN = 4 # 
-enums['PinsList'][4] = EnumEntry('QUICK_CONNECTOR_PIN', '''''')
-PinsList_ENUM_END = 5 # 
-enums['PinsList'][5] = EnumEntry('PinsList_ENUM_END', '''''')
+PinsList_ENUM_END = 3 # 
+enums['PinsList'][3] = EnumEntry('PinsList_ENUM_END', '''''')
 
 # message IDs
 MAVLINK_MSG_ID_BAD_DATA = -1
@@ -479,49 +483,52 @@ MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC = 3
 MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC = 4
 MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC = 5
 MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC = 6
-MAVLINK_MSG_ID_WIGGLE_SERVO_TC = 7
-MAVLINK_MSG_ID_RESET_SERVO_TC = 8
+MAVLINK_MSG_ID_RESET_SERVO_TC = 7
+MAVLINK_MSG_ID_WIGGLE_SERVO_TC = 8
 MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC = 9
 MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC = 10
 MAVLINK_MSG_ID_SET_ORIENTATION_TC = 11
-MAVLINK_MSG_ID_SET_COORDINATES_TC = 12
-MAVLINK_MSG_ID_RAW_EVENT_TC = 13
-MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC = 14
-MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC = 15
-MAVLINK_MSG_ID_SET_ALGORITHM_TC = 16
-MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC = 17
-MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC = 18
-MAVLINK_MSG_ID_CONRIG_STATE_TC = 19
-MAVLINK_MSG_ID_SET_IGNITION_TIME_TC = 20
-MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC = 21
-MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC = 22
-MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC = 23
-MAVLINK_MSG_ID_SET_COOLING_TIME_TC = 24
+MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC = 12
+MAVLINK_MSG_ID_SET_COORDINATES_TC = 13
+MAVLINK_MSG_ID_RAW_EVENT_TC = 14
+MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC = 15
+MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC = 16
+MAVLINK_MSG_ID_SET_ALGORITHM_TC = 17
+MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC = 30
+MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC = 31
+MAVLINK_MSG_ID_CONRIG_STATE_TC = 32
+MAVLINK_MSG_ID_SET_IGNITION_TIME_TC = 33
+MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC = 34
+MAVLINK_MSG_ID_SET_COOLING_TIME_TC = 35
+MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC = 60
+MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC = 61
+MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC = 62
+MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC = 63
+MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC = 64
+MAVLINK_MSG_ID_ARP_COMMAND_TC = 65
 MAVLINK_MSG_ID_ACK_TM = 100
 MAVLINK_MSG_ID_NACK_TM = 101
-MAVLINK_MSG_ID_GPS_TM = 102
-MAVLINK_MSG_ID_IMU_TM = 103
-MAVLINK_MSG_ID_PRESSURE_TM = 104
-MAVLINK_MSG_ID_ADC_TM = 105
-MAVLINK_MSG_ID_VOLTAGE_TM = 106
-MAVLINK_MSG_ID_CURRENT_TM = 107
-MAVLINK_MSG_ID_TEMP_TM = 108
-MAVLINK_MSG_ID_LOAD_TM = 109
-MAVLINK_MSG_ID_ATTITUDE_TM = 110
-MAVLINK_MSG_ID_SENSOR_STATE_TM = 111
-MAVLINK_MSG_ID_SERVO_TM = 112
-MAVLINK_MSG_ID_PIN_TM = 113
-MAVLINK_MSG_ID_REGISTRY_FLOAT_TM = 114
-MAVLINK_MSG_ID_REGISTRY_INT_TM = 115
-MAVLINK_MSG_ID_REGISTRY_COORD_TM = 116
-MAVLINK_MSG_ID_RECEIVER_TM = 150
-MAVLINK_MSG_ID_ARP_TM = 169
-MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC = 170
-MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC = 171
+MAVLINK_MSG_ID_WACK_TM = 102
+MAVLINK_MSG_ID_GPS_TM = 103
+MAVLINK_MSG_ID_IMU_TM = 104
+MAVLINK_MSG_ID_PRESSURE_TM = 105
+MAVLINK_MSG_ID_ADC_TM = 106
+MAVLINK_MSG_ID_VOLTAGE_TM = 107
+MAVLINK_MSG_ID_CURRENT_TM = 108
+MAVLINK_MSG_ID_TEMP_TM = 109
+MAVLINK_MSG_ID_LOAD_TM = 110
+MAVLINK_MSG_ID_ATTITUDE_TM = 111
+MAVLINK_MSG_ID_SENSOR_STATE_TM = 112
+MAVLINK_MSG_ID_SERVO_TM = 113
+MAVLINK_MSG_ID_PIN_TM = 114
+MAVLINK_MSG_ID_REGISTRY_FLOAT_TM = 115
+MAVLINK_MSG_ID_REGISTRY_INT_TM = 116
+MAVLINK_MSG_ID_REGISTRY_COORD_TM = 117
+MAVLINK_MSG_ID_ARP_TM = 150
 MAVLINK_MSG_ID_SYS_TM = 200
-MAVLINK_MSG_ID_FSM_TM = 201
-MAVLINK_MSG_ID_LOGGER_TM = 202
-MAVLINK_MSG_ID_MAVLINK_STATS_TM = 203
+MAVLINK_MSG_ID_LOGGER_TM = 201
+MAVLINK_MSG_ID_MAVLINK_STATS_TM = 202
+MAVLINK_MSG_ID_CAN_STATS_TM = 203
 MAVLINK_MSG_ID_TASK_STATS_TM = 204
 MAVLINK_MSG_ID_ADA_TM = 205
 MAVLINK_MSG_ID_NAS_TM = 206
@@ -727,12 +734,12 @@ class MAVLink_set_servo_angle_tc_message(MAVLink_message):
         def pack(self, mav, force_mavlink1=False):
                 return MAVLink_message.pack(self, mav, 215, struct.pack('<fB', self.angle, self.servo_id), force_mavlink1=force_mavlink1)
 
-class MAVLink_wiggle_servo_tc_message(MAVLink_message):
+class MAVLink_reset_servo_tc_message(MAVLink_message):
         '''
-        Wiggles the specified servo
+        Resets the specified servo
         '''
-        id = MAVLINK_MSG_ID_WIGGLE_SERVO_TC
-        name = 'WIGGLE_SERVO_TC'
+        id = MAVLINK_MSG_ID_RESET_SERVO_TC
+        name = 'RESET_SERVO_TC'
         fieldnames = ['servo_id']
         ordered_fieldnames = ['servo_id']
         fieldtypes = ['uint8_t']
@@ -744,27 +751,27 @@ class MAVLink_wiggle_servo_tc_message(MAVLink_message):
         orders = [0]
         lengths = [1]
         array_lengths = [0]
-        crc_extra = 160
+        crc_extra = 226
         unpacker = struct.Struct('<B')
         instance_field = None
         instance_offset = -1
 
         def __init__(self, servo_id):
-                MAVLink_message.__init__(self, MAVLink_wiggle_servo_tc_message.id, MAVLink_wiggle_servo_tc_message.name)
-                self._fieldnames = MAVLink_wiggle_servo_tc_message.fieldnames
-                self._instance_field = MAVLink_wiggle_servo_tc_message.instance_field
-                self._instance_offset = MAVLink_wiggle_servo_tc_message.instance_offset
+                MAVLink_message.__init__(self, MAVLink_reset_servo_tc_message.id, MAVLink_reset_servo_tc_message.name)
+                self._fieldnames = MAVLink_reset_servo_tc_message.fieldnames
+                self._instance_field = MAVLink_reset_servo_tc_message.instance_field
+                self._instance_offset = MAVLink_reset_servo_tc_message.instance_offset
                 self.servo_id = servo_id
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 160, struct.pack('<B', self.servo_id), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 226, struct.pack('<B', self.servo_id), force_mavlink1=force_mavlink1)
 
-class MAVLink_reset_servo_tc_message(MAVLink_message):
+class MAVLink_wiggle_servo_tc_message(MAVLink_message):
         '''
-        Resets the specified servo
+        Wiggles the specified servo
         '''
-        id = MAVLINK_MSG_ID_RESET_SERVO_TC
-        name = 'RESET_SERVO_TC'
+        id = MAVLINK_MSG_ID_WIGGLE_SERVO_TC
+        name = 'WIGGLE_SERVO_TC'
         fieldnames = ['servo_id']
         ordered_fieldnames = ['servo_id']
         fieldtypes = ['uint8_t']
@@ -776,20 +783,20 @@ class MAVLink_reset_servo_tc_message(MAVLink_message):
         orders = [0]
         lengths = [1]
         array_lengths = [0]
-        crc_extra = 226
+        crc_extra = 160
         unpacker = struct.Struct('<B')
         instance_field = None
         instance_offset = -1
 
         def __init__(self, servo_id):
-                MAVLink_message.__init__(self, MAVLink_reset_servo_tc_message.id, MAVLink_reset_servo_tc_message.name)
-                self._fieldnames = MAVLink_reset_servo_tc_message.fieldnames
-                self._instance_field = MAVLink_reset_servo_tc_message.instance_field
-                self._instance_offset = MAVLink_reset_servo_tc_message.instance_offset
+                MAVLink_message.__init__(self, MAVLink_wiggle_servo_tc_message.id, MAVLink_wiggle_servo_tc_message.name)
+                self._fieldnames = MAVLink_wiggle_servo_tc_message.fieldnames
+                self._instance_field = MAVLink_wiggle_servo_tc_message.instance_field
+                self._instance_offset = MAVLink_wiggle_servo_tc_message.instance_offset
                 self.servo_id = servo_id
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 226, struct.pack('<B', self.servo_id), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 160, struct.pack('<B', self.servo_id), force_mavlink1=force_mavlink1)
 
 class MAVLink_set_reference_altitude_tc_message(MAVLink_message):
         '''
@@ -889,6 +896,42 @@ class MAVLink_set_orientation_tc_message(MAVLink_message):
         def pack(self, mav, force_mavlink1=False):
                 return MAVLink_message.pack(self, mav, 71, struct.pack('<fff', self.yaw, self.pitch, self.roll), force_mavlink1=force_mavlink1)
 
+class MAVLink_set_orientation_quat_tc_message(MAVLink_message):
+        '''
+        Sets current orientation for the navigation system using a
+        quaternion
+        '''
+        id = MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC
+        name = 'SET_ORIENTATION_QUAT_TC'
+        fieldnames = ['quat_x', 'quat_y', 'quat_z', 'quat_w']
+        ordered_fieldnames = ['quat_x', 'quat_y', 'quat_z', 'quat_w']
+        fieldtypes = ['float', 'float', 'float', 'float']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {}
+        fieldunits_by_name = {}
+        format = '<ffff'
+        native_format = bytearray('<ffff', 'ascii')
+        orders = [0, 1, 2, 3]
+        lengths = [1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0]
+        crc_extra = 168
+        unpacker = struct.Struct('<ffff')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, quat_x, quat_y, quat_z, quat_w):
+                MAVLink_message.__init__(self, MAVLink_set_orientation_quat_tc_message.id, MAVLink_set_orientation_quat_tc_message.name)
+                self._fieldnames = MAVLink_set_orientation_quat_tc_message.fieldnames
+                self._instance_field = MAVLink_set_orientation_quat_tc_message.instance_field
+                self._instance_offset = MAVLink_set_orientation_quat_tc_message.instance_offset
+                self.quat_x = quat_x
+                self.quat_y = quat_y
+                self.quat_z = quat_z
+                self.quat_w = quat_w
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 168, struct.pack('<ffff', self.quat_x, self.quat_y, self.quat_z, self.quat_w), force_mavlink1=force_mavlink1)
+
 class MAVLink_set_coordinates_tc_message(MAVLink_message):
         '''
         Sets current coordinates
@@ -1023,7 +1066,7 @@ class MAVLink_set_target_coordinates_tc_message(MAVLink_message):
 
 class MAVLink_set_algorithm_tc_message(MAVLink_message):
         '''
-        Sets the algorithm number (for parafoil guidance and GSE tars)
+        Sets the algorithm number (for parafoil guidance)
         '''
         id = MAVLINK_MSG_ID_SET_ALGORITHM_TC
         name = 'SET_ALGORITHM_TC'
@@ -1191,6 +1234,71 @@ class MAVLink_set_ignition_time_tc_message(MAVLink_message):
         def pack(self, mav, force_mavlink1=False):
                 return MAVLink_message.pack(self, mav, 79, struct.pack('<I', self.timing), force_mavlink1=force_mavlink1)
 
+class MAVLink_set_nitrogen_time_tc_message(MAVLink_message):
+        '''
+        Sets the time in ms that the nitrogen will stay open
+        '''
+        id = MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC
+        name = 'SET_NITROGEN_TIME_TC'
+        fieldnames = ['timing']
+        ordered_fieldnames = ['timing']
+        fieldtypes = ['uint32_t']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {}
+        fieldunits_by_name = {"timing": "ms"}
+        format = '<I'
+        native_format = bytearray('<I', 'ascii')
+        orders = [0]
+        lengths = [1]
+        array_lengths = [0]
+        crc_extra = 167
+        unpacker = struct.Struct('<I')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, timing):
+                MAVLink_message.__init__(self, MAVLink_set_nitrogen_time_tc_message.id, MAVLink_set_nitrogen_time_tc_message.name)
+                self._fieldnames = MAVLink_set_nitrogen_time_tc_message.fieldnames
+                self._instance_field = MAVLink_set_nitrogen_time_tc_message.instance_field
+                self._instance_offset = MAVLink_set_nitrogen_time_tc_message.instance_offset
+                self.timing = timing
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 167, struct.pack('<I', self.timing), force_mavlink1=force_mavlink1)
+
+class MAVLink_set_cooling_time_tc_message(MAVLink_message):
+        '''
+        Sets the time in ms that the system will wait before disarming
+        after firing
+        '''
+        id = MAVLINK_MSG_ID_SET_COOLING_TIME_TC
+        name = 'SET_COOLING_TIME_TC'
+        fieldnames = ['timing']
+        ordered_fieldnames = ['timing']
+        fieldtypes = ['uint32_t']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {}
+        fieldunits_by_name = {"timing": "ms"}
+        format = '<I'
+        native_format = bytearray('<I', 'ascii')
+        orders = [0]
+        lengths = [1]
+        array_lengths = [0]
+        crc_extra = 84
+        unpacker = struct.Struct('<I')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, timing):
+                MAVLink_message.__init__(self, MAVLink_set_cooling_time_tc_message.id, MAVLink_set_cooling_time_tc_message.name)
+                self._fieldnames = MAVLink_set_cooling_time_tc_message.fieldnames
+                self._instance_field = MAVLink_set_cooling_time_tc_message.instance_field
+                self._instance_offset = MAVLink_set_cooling_time_tc_message.instance_offset
+                self.timing = timing
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 84, struct.pack('<I', self.timing), force_mavlink1=force_mavlink1)
+
 class MAVLink_set_stepper_angle_tc_message(MAVLink_message):
         '''
         Move the stepper of a certain angle
@@ -1257,75 +1365,144 @@ class MAVLink_set_stepper_steps_tc_message(MAVLink_message):
         def pack(self, mav, force_mavlink1=False):
                 return MAVLink_message.pack(self, mav, 246, struct.pack('<fB', self.steps, self.stepper_id), force_mavlink1=force_mavlink1)
 
-class MAVLink_set_nitrogen_time_tc_message(MAVLink_message):
+class MAVLink_set_stepper_multiplier_tc_message(MAVLink_message):
         '''
-        Sets the time in ms that the nitrogen will stay open
+        Set the multiplier of the stepper
         '''
-        id = MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC
-        name = 'SET_NITROGEN_TIME_TC'
-        fieldnames = ['timing']
-        ordered_fieldnames = ['timing']
-        fieldtypes = ['uint32_t']
+        id = MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC
+        name = 'SET_STEPPER_MULTIPLIER_TC'
+        fieldnames = ['stepper_id', 'multiplier']
+        ordered_fieldnames = ['multiplier', 'stepper_id']
+        fieldtypes = ['uint8_t', 'float']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timing": "ms"}
-        format = '<I'
-        native_format = bytearray('<I', 'ascii')
-        orders = [0]
-        lengths = [1]
-        array_lengths = [0]
-        crc_extra = 167
-        unpacker = struct.Struct('<I')
+        fieldunits_by_name = {}
+        format = '<fB'
+        native_format = bytearray('<fB', 'ascii')
+        orders = [1, 0]
+        lengths = [1, 1]
+        array_lengths = [0, 0]
+        crc_extra = 173
+        unpacker = struct.Struct('<fB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timing):
-                MAVLink_message.__init__(self, MAVLink_set_nitrogen_time_tc_message.id, MAVLink_set_nitrogen_time_tc_message.name)
-                self._fieldnames = MAVLink_set_nitrogen_time_tc_message.fieldnames
-                self._instance_field = MAVLink_set_nitrogen_time_tc_message.instance_field
-                self._instance_offset = MAVLink_set_nitrogen_time_tc_message.instance_offset
-                self.timing = timing
+        def __init__(self, stepper_id, multiplier):
+                MAVLink_message.__init__(self, MAVLink_set_stepper_multiplier_tc_message.id, MAVLink_set_stepper_multiplier_tc_message.name)
+                self._fieldnames = MAVLink_set_stepper_multiplier_tc_message.fieldnames
+                self._instance_field = MAVLink_set_stepper_multiplier_tc_message.instance_field
+                self._instance_offset = MAVLink_set_stepper_multiplier_tc_message.instance_offset
+                self.stepper_id = stepper_id
+                self.multiplier = multiplier
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 167, struct.pack('<I', self.timing), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 173, struct.pack('<fB', self.multiplier, self.stepper_id), force_mavlink1=force_mavlink1)
 
-class MAVLink_set_cooling_time_tc_message(MAVLink_message):
+class MAVLink_set_antenna_coordinates_arp_tc_message(MAVLink_message):
         '''
-        Sets the time in ms that the system will wait before disarming
-        after firing
+        Sets current antennas coordinates
         '''
-        id = MAVLINK_MSG_ID_SET_COOLING_TIME_TC
-        name = 'SET_COOLING_TIME_TC'
-        fieldnames = ['timing']
-        ordered_fieldnames = ['timing']
-        fieldtypes = ['uint32_t']
+        id = MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC
+        name = 'SET_ANTENNA_COORDINATES_ARP_TC'
+        fieldnames = ['latitude', 'longitude', 'height']
+        ordered_fieldnames = ['latitude', 'longitude', 'height']
+        fieldtypes = ['float', 'float', 'float']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timing": "ms"}
-        format = '<I'
-        native_format = bytearray('<I', 'ascii')
+        fieldunits_by_name = {"latitude": "deg", "longitude": "deg", "height": "m"}
+        format = '<fff'
+        native_format = bytearray('<fff', 'ascii')
+        orders = [0, 1, 2]
+        lengths = [1, 1, 1]
+        array_lengths = [0, 0, 0]
+        crc_extra = 183
+        unpacker = struct.Struct('<fff')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, latitude, longitude, height):
+                MAVLink_message.__init__(self, MAVLink_set_antenna_coordinates_arp_tc_message.id, MAVLink_set_antenna_coordinates_arp_tc_message.name)
+                self._fieldnames = MAVLink_set_antenna_coordinates_arp_tc_message.fieldnames
+                self._instance_field = MAVLink_set_antenna_coordinates_arp_tc_message.instance_field
+                self._instance_offset = MAVLink_set_antenna_coordinates_arp_tc_message.instance_offset
+                self.latitude = latitude
+                self.longitude = longitude
+                self.height = height
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 183, struct.pack('<fff', self.latitude, self.longitude, self.height), force_mavlink1=force_mavlink1)
+
+class MAVLink_set_rocket_coordinates_arp_tc_message(MAVLink_message):
+        '''
+        Sets current rocket coordinates
+        '''
+        id = MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC
+        name = 'SET_ROCKET_COORDINATES_ARP_TC'
+        fieldnames = ['latitude', 'longitude', 'height']
+        ordered_fieldnames = ['latitude', 'longitude', 'height']
+        fieldtypes = ['float', 'float', 'float']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {}
+        fieldunits_by_name = {"latitude": "deg", "longitude": "deg", "height": "m"}
+        format = '<fff'
+        native_format = bytearray('<fff', 'ascii')
+        orders = [0, 1, 2]
+        lengths = [1, 1, 1]
+        array_lengths = [0, 0, 0]
+        crc_extra = 220
+        unpacker = struct.Struct('<fff')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, latitude, longitude, height):
+                MAVLink_message.__init__(self, MAVLink_set_rocket_coordinates_arp_tc_message.id, MAVLink_set_rocket_coordinates_arp_tc_message.name)
+                self._fieldnames = MAVLink_set_rocket_coordinates_arp_tc_message.fieldnames
+                self._instance_field = MAVLink_set_rocket_coordinates_arp_tc_message.instance_field
+                self._instance_offset = MAVLink_set_rocket_coordinates_arp_tc_message.instance_offset
+                self.latitude = latitude
+                self.longitude = longitude
+                self.height = height
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 220, struct.pack('<fff', self.latitude, self.longitude, self.height), force_mavlink1=force_mavlink1)
+
+class MAVLink_arp_command_tc_message(MAVLink_message):
+        '''
+        TC containing a command with no parameters that trigger some
+        action
+        '''
+        id = MAVLINK_MSG_ID_ARP_COMMAND_TC
+        name = 'ARP_COMMAND_TC'
+        fieldnames = ['command_id']
+        ordered_fieldnames = ['command_id']
+        fieldtypes = ['uint8_t']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {}
+        fieldunits_by_name = {}
+        format = '<B'
+        native_format = bytearray('<B', 'ascii')
         orders = [0]
         lengths = [1]
         array_lengths = [0]
-        crc_extra = 84
-        unpacker = struct.Struct('<I')
+        crc_extra = 181
+        unpacker = struct.Struct('<B')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timing):
-                MAVLink_message.__init__(self, MAVLink_set_cooling_time_tc_message.id, MAVLink_set_cooling_time_tc_message.name)
-                self._fieldnames = MAVLink_set_cooling_time_tc_message.fieldnames
-                self._instance_field = MAVLink_set_cooling_time_tc_message.instance_field
-                self._instance_offset = MAVLink_set_cooling_time_tc_message.instance_offset
-                self.timing = timing
+        def __init__(self, command_id):
+                MAVLink_message.__init__(self, MAVLink_arp_command_tc_message.id, MAVLink_arp_command_tc_message.name)
+                self._fieldnames = MAVLink_arp_command_tc_message.fieldnames
+                self._instance_field = MAVLink_arp_command_tc_message.instance_field
+                self._instance_offset = MAVLink_arp_command_tc_message.instance_offset
+                self.command_id = command_id
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 84, struct.pack('<I', self.timing), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 181, struct.pack('<B', self.command_id), force_mavlink1=force_mavlink1)
 
 class MAVLink_ack_tm_message(MAVLink_message):
         '''
         TM containing an ACK message to notify that the message has
-        been received
+        been processed correctly
         '''
         id = MAVLINK_MSG_ID_ACK_TM
         name = 'ACK_TM'
@@ -1363,32 +1540,68 @@ class MAVLink_nack_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_NACK_TM
         name = 'NACK_TM'
-        fieldnames = ['recv_msgid', 'seq_ack']
-        ordered_fieldnames = ['recv_msgid', 'seq_ack']
-        fieldtypes = ['uint8_t', 'uint8_t']
+        fieldnames = ['recv_msgid', 'seq_ack', 'err_id']
+        ordered_fieldnames = ['err_id', 'recv_msgid', 'seq_ack']
+        fieldtypes = ['uint8_t', 'uint8_t', 'uint16_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
         fieldunits_by_name = {}
-        format = '<BB'
-        native_format = bytearray('<BB', 'ascii')
-        orders = [0, 1]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 146
-        unpacker = struct.Struct('<BB')
+        format = '<HBB'
+        native_format = bytearray('<HBB', 'ascii')
+        orders = [1, 2, 0]
+        lengths = [1, 1, 1]
+        array_lengths = [0, 0, 0]
+        crc_extra = 251
+        unpacker = struct.Struct('<HBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, recv_msgid, seq_ack):
+        def __init__(self, recv_msgid, seq_ack, err_id):
                 MAVLink_message.__init__(self, MAVLink_nack_tm_message.id, MAVLink_nack_tm_message.name)
                 self._fieldnames = MAVLink_nack_tm_message.fieldnames
                 self._instance_field = MAVLink_nack_tm_message.instance_field
                 self._instance_offset = MAVLink_nack_tm_message.instance_offset
                 self.recv_msgid = recv_msgid
                 self.seq_ack = seq_ack
+                self.err_id = err_id
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 146, struct.pack('<BB', self.recv_msgid, self.seq_ack), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 251, struct.pack('<HBB', self.err_id, self.recv_msgid, self.seq_ack), force_mavlink1=force_mavlink1)
+
+class MAVLink_wack_tm_message(MAVLink_message):
+        '''
+        TM containing an ACK message to notify that the message has
+        been processed with a warning
+        '''
+        id = MAVLINK_MSG_ID_WACK_TM
+        name = 'WACK_TM'
+        fieldnames = ['recv_msgid', 'seq_ack', 'err_id']
+        ordered_fieldnames = ['err_id', 'recv_msgid', 'seq_ack']
+        fieldtypes = ['uint8_t', 'uint8_t', 'uint16_t']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {}
+        fieldunits_by_name = {}
+        format = '<HBB'
+        native_format = bytearray('<HBB', 'ascii')
+        orders = [1, 2, 0]
+        lengths = [1, 1, 1]
+        array_lengths = [0, 0, 0]
+        crc_extra = 51
+        unpacker = struct.Struct('<HBB')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, recv_msgid, seq_ack, err_id):
+                MAVLink_message.__init__(self, MAVLink_wack_tm_message.id, MAVLink_wack_tm_message.name)
+                self._fieldnames = MAVLink_wack_tm_message.fieldnames
+                self._instance_field = MAVLink_wack_tm_message.instance_field
+                self._instance_offset = MAVLink_wack_tm_message.instance_offset
+                self.recv_msgid = recv_msgid
+                self.seq_ack = seq_ack
+                self.err_id = err_id
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 51, struct.pack('<HBB', self.err_id, self.recv_msgid, self.seq_ack), force_mavlink1=force_mavlink1)
 
 class MAVLink_gps_tm_message(MAVLink_message):
         '''
@@ -1732,32 +1945,33 @@ class MAVLink_sensor_state_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_SENSOR_STATE_TM
         name = 'SENSOR_STATE_TM'
-        fieldnames = ['sensor_name', 'state']
-        ordered_fieldnames = ['sensor_name', 'state']
-        fieldtypes = ['char', 'uint8_t']
+        fieldnames = ['sensor_name', 'initialized', 'enabled']
+        ordered_fieldnames = ['sensor_name', 'initialized', 'enabled']
+        fieldtypes = ['char', 'uint8_t', 'uint8_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
         fieldunits_by_name = {}
-        format = '<20sB'
-        native_format = bytearray('<cB', 'ascii')
-        orders = [0, 1]
-        lengths = [1, 1]
-        array_lengths = [20, 0]
-        crc_extra = 155
-        unpacker = struct.Struct('<20sB')
+        format = '<20sBB'
+        native_format = bytearray('<cBB', 'ascii')
+        orders = [0, 1, 2]
+        lengths = [1, 1, 1]
+        array_lengths = [20, 0, 0]
+        crc_extra = 165
+        unpacker = struct.Struct('<20sBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, sensor_name, state):
+        def __init__(self, sensor_name, initialized, enabled):
                 MAVLink_message.__init__(self, MAVLink_sensor_state_tm_message.id, MAVLink_sensor_state_tm_message.name)
                 self._fieldnames = MAVLink_sensor_state_tm_message.fieldnames
                 self._instance_field = MAVLink_sensor_state_tm_message.instance_field
                 self._instance_offset = MAVLink_sensor_state_tm_message.instance_offset
                 self.sensor_name = sensor_name
-                self.state = state
+                self.initialized = initialized
+                self.enabled = enabled
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 155, struct.pack('<20sB', self.sensor_name, self.state), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 165, struct.pack('<20sBB', self.sensor_name, self.initialized, self.enabled), force_mavlink1=force_mavlink1)
 
 class MAVLink_servo_tm_message(MAVLink_message):
         '''
@@ -1916,74 +2130,23 @@ class MAVLink_registry_coord_tm_message(MAVLink_message):
         lengths = [1, 1, 1, 1, 1]
         array_lengths = [0, 0, 0, 0, 20]
         crc_extra = 234
-        unpacker = struct.Struct('<QIff20s')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, key_id, key_name, latitude, longitude):
-                MAVLink_message.__init__(self, MAVLink_registry_coord_tm_message.id, MAVLink_registry_coord_tm_message.name)
-                self._fieldnames = MAVLink_registry_coord_tm_message.fieldnames
-                self._instance_field = MAVLink_registry_coord_tm_message.instance_field
-                self._instance_offset = MAVLink_registry_coord_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.key_id = key_id
-                self.key_name = key_name
-                self.latitude = latitude
-                self.longitude = longitude
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 234, struct.pack('<QIff20s', self.timestamp, self.key_id, self.latitude, self.longitude, self.key_name), force_mavlink1=force_mavlink1)
-
-class MAVLink_receiver_tm_message(MAVLink_message):
-        '''
-
-        '''
-        id = MAVLINK_MSG_ID_RECEIVER_TM
-        name = 'RECEIVER_TM'
-        fieldnames = ['timestamp', 'main_radio_present', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'main_rx_rssi', 'main_rx_fei', 'payload_radio_present', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'payload_rx_rssi', 'payload_rx_fei', 'ethernet_present', 'ethernet_status', 'battery_voltage']
-        ordered_fieldnames = ['timestamp', 'main_rx_rssi', 'main_rx_fei', 'payload_rx_rssi', 'payload_rx_fei', 'battery_voltage', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'main_radio_present', 'payload_radio_present', 'ethernet_present', 'ethernet_status']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'float', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'float', 'uint8_t', 'uint8_t', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "main_tx_bitrate": "b/s", "main_rx_bitrate": "b/s", "main_rx_rssi": "dBm", "main_rx_fei": "Hz", "payload_tx_bitrate": "b/s", "payload_rx_bitrate": "b/s", "payload_rx_rssi": "dBm", "payload_rx_fei": "Hz", "battery_voltage": "V"}
-        format = '<QfffffHHHHHHHHHHBBBB'
-        native_format = bytearray('<QfffffHHHHHHHHHHBBBB', 'ascii')
-        orders = [0, 16, 6, 7, 8, 9, 10, 1, 2, 17, 11, 12, 13, 14, 15, 3, 4, 18, 19, 5]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 117
-        unpacker = struct.Struct('<QfffffHHHHHHHHHHBBBB')
+        unpacker = struct.Struct('<QIff20s')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage):
-                MAVLink_message.__init__(self, MAVLink_receiver_tm_message.id, MAVLink_receiver_tm_message.name)
-                self._fieldnames = MAVLink_receiver_tm_message.fieldnames
-                self._instance_field = MAVLink_receiver_tm_message.instance_field
-                self._instance_offset = MAVLink_receiver_tm_message.instance_offset
+        def __init__(self, timestamp, key_id, key_name, latitude, longitude):
+                MAVLink_message.__init__(self, MAVLink_registry_coord_tm_message.id, MAVLink_registry_coord_tm_message.name)
+                self._fieldnames = MAVLink_registry_coord_tm_message.fieldnames
+                self._instance_field = MAVLink_registry_coord_tm_message.instance_field
+                self._instance_offset = MAVLink_registry_coord_tm_message.instance_offset
                 self.timestamp = timestamp
-                self.main_radio_present = main_radio_present
-                self.main_packet_tx_error_count = main_packet_tx_error_count
-                self.main_tx_bitrate = main_tx_bitrate
-                self.main_packet_rx_success_count = main_packet_rx_success_count
-                self.main_packet_rx_drop_count = main_packet_rx_drop_count
-                self.main_rx_bitrate = main_rx_bitrate
-                self.main_rx_rssi = main_rx_rssi
-                self.main_rx_fei = main_rx_fei
-                self.payload_radio_present = payload_radio_present
-                self.payload_packet_tx_error_count = payload_packet_tx_error_count
-                self.payload_tx_bitrate = payload_tx_bitrate
-                self.payload_packet_rx_success_count = payload_packet_rx_success_count
-                self.payload_packet_rx_drop_count = payload_packet_rx_drop_count
-                self.payload_rx_bitrate = payload_rx_bitrate
-                self.payload_rx_rssi = payload_rx_rssi
-                self.payload_rx_fei = payload_rx_fei
-                self.ethernet_present = ethernet_present
-                self.ethernet_status = ethernet_status
-                self.battery_voltage = battery_voltage
+                self.key_id = key_id
+                self.key_name = key_name
+                self.latitude = latitude
+                self.longitude = longitude
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 117, struct.pack('<QfffffHHHHHHHHHHBBBB', self.timestamp, self.main_rx_rssi, self.main_rx_fei, self.payload_rx_rssi, self.payload_rx_fei, self.battery_voltage, self.main_packet_tx_error_count, self.main_tx_bitrate, self.main_packet_rx_success_count, self.main_packet_rx_drop_count, self.main_rx_bitrate, self.payload_packet_tx_error_count, self.payload_tx_bitrate, self.payload_packet_rx_success_count, self.payload_packet_rx_drop_count, self.payload_rx_bitrate, self.main_radio_present, self.payload_radio_present, self.ethernet_present, self.ethernet_status), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 234, struct.pack('<QIff20s', self.timestamp, self.key_id, self.latitude, self.longitude, self.key_name), force_mavlink1=force_mavlink1)
 
 class MAVLink_arp_tm_message(MAVLink_message):
         '''
@@ -1991,23 +2154,23 @@ class MAVLink_arp_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_ARP_TM
         name = 'ARP_TM'
-        fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'gps_fix', 'main_radio_present', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'main_rx_rssi', 'ethernet_present', 'ethernet_status', 'battery_voltage']
-        ordered_fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'main_rx_rssi', 'battery_voltage', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'gps_fix', 'main_radio_present', 'ethernet_present', 'ethernet_status']
-        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'uint8_t', 'uint8_t', 'float']
+        fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'gps_fix', 'main_radio_present', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'main_rx_rssi', 'payload_radio_present', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'payload_rx_rssi', 'ethernet_present', 'ethernet_status', 'battery_voltage']
+        ordered_fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'main_rx_rssi', 'payload_rx_rssi', 'battery_voltage', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'gps_fix', 'main_radio_present', 'payload_radio_present', 'ethernet_present', 'ethernet_status']
+        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'uint8_t', 'uint8_t', 'float']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "yaw": "deg", "pitch": "deg", "roll": "deg", "target_yaw": "deg", "target_pitch": "deg", "stepperX_pos": "deg", "stepperX_delta": "deg", "stepperX_speed": "rps", "stepperY_pos": "deg", "stepperY_delta": "deg", "stepperY_speed": "rps", "gps_latitude": "deg", "gps_longitude": "deg", "gps_height": "m", "main_tx_bitrate": "b/s", "main_rx_bitrate": "b/s", "main_rx_rssi": "dBm", "battery_voltage": "V"}
-        format = '<QffffffffffffffffHHHHHBBBB'
-        native_format = bytearray('<QffffffffffffffffHHHHHBBBB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 22, 23, 17, 18, 19, 20, 21, 15, 24, 25, 16]
-        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]
-        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]
-        crc_extra = 2
-        unpacker = struct.Struct('<QffffffffffffffffHHHHHBBBB')
+        fieldunits_by_name = {"timestamp": "us", "yaw": "deg", "pitch": "deg", "roll": "deg", "target_yaw": "deg", "target_pitch": "deg", "stepperX_pos": "deg", "stepperX_delta": "deg", "stepperX_speed": "rps", "stepperY_pos": "deg", "stepperY_delta": "deg", "stepperY_speed": "rps", "gps_latitude": "deg", "gps_longitude": "deg", "gps_height": "m", "main_tx_bitrate": "b/s", "main_rx_bitrate": "b/s", "main_rx_rssi": "dBm", "payload_tx_bitrate": "b/s", "payload_rx_bitrate": "b/s", "payload_rx_rssi": "dBm", "battery_voltage": "V"}
+        format = '<QfffffffffffffffffHHHHHHHHHHBBBBB'
+        native_format = bytearray('<QfffffffffffffffffHHHHHHHHHHBBBBB', 'ascii')
+        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 28, 29, 18, 19, 20, 21, 22, 15, 30, 23, 24, 25, 26, 27, 16, 31, 32, 17]
+        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 22
+        unpacker = struct.Struct('<QfffffffffffffffffHHHHHHHHHHBBBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage):
+        def __init__(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, ethernet_present, ethernet_status, battery_voltage):
                 MAVLink_message.__init__(self, MAVLink_arp_tm_message.id, MAVLink_arp_tm_message.name)
                 self._fieldnames = MAVLink_arp_tm_message.fieldnames
                 self._instance_field = MAVLink_arp_tm_message.instance_field
@@ -2035,78 +2198,19 @@ class MAVLink_arp_tm_message(MAVLink_message):
                 self.main_packet_rx_drop_count = main_packet_rx_drop_count
                 self.main_rx_bitrate = main_rx_bitrate
                 self.main_rx_rssi = main_rx_rssi
+                self.payload_radio_present = payload_radio_present
+                self.payload_packet_tx_error_count = payload_packet_tx_error_count
+                self.payload_tx_bitrate = payload_tx_bitrate
+                self.payload_packet_rx_success_count = payload_packet_rx_success_count
+                self.payload_packet_rx_drop_count = payload_packet_rx_drop_count
+                self.payload_rx_bitrate = payload_rx_bitrate
+                self.payload_rx_rssi = payload_rx_rssi
                 self.ethernet_present = ethernet_present
                 self.ethernet_status = ethernet_status
                 self.battery_voltage = battery_voltage
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 2, struct.pack('<QffffffffffffffffHHHHHBBBB', self.timestamp, self.yaw, self.pitch, self.roll, self.target_yaw, self.target_pitch, self.stepperX_pos, self.stepperX_delta, self.stepperX_speed, self.stepperY_pos, self.stepperY_delta, self.stepperY_speed, self.gps_latitude, self.gps_longitude, self.gps_height, self.main_rx_rssi, self.battery_voltage, self.main_packet_tx_error_count, self.main_tx_bitrate, self.main_packet_rx_success_count, self.main_packet_rx_drop_count, self.main_rx_bitrate, self.gps_fix, self.main_radio_present, self.ethernet_present, self.ethernet_status), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_antenna_coordinates_arp_tc_message(MAVLink_message):
-        '''
-        Sets current antennas coordinates
-        '''
-        id = MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC
-        name = 'SET_ANTENNA_COORDINATES_ARP_TC'
-        fieldnames = ['latitude', 'longitude']
-        ordered_fieldnames = ['latitude', 'longitude']
-        fieldtypes = ['float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"latitude": "deg", "longitude": "deg"}
-        format = '<ff'
-        native_format = bytearray('<ff', 'ascii')
-        orders = [0, 1]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 202
-        unpacker = struct.Struct('<ff')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, latitude, longitude):
-                MAVLink_message.__init__(self, MAVLink_set_antenna_coordinates_arp_tc_message.id, MAVLink_set_antenna_coordinates_arp_tc_message.name)
-                self._fieldnames = MAVLink_set_antenna_coordinates_arp_tc_message.fieldnames
-                self._instance_field = MAVLink_set_antenna_coordinates_arp_tc_message.instance_field
-                self._instance_offset = MAVLink_set_antenna_coordinates_arp_tc_message.instance_offset
-                self.latitude = latitude
-                self.longitude = longitude
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 202, struct.pack('<ff', self.latitude, self.longitude), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_rocket_coordinates_arp_tc_message(MAVLink_message):
-        '''
-        Sets current rocket coordinates
-        '''
-        id = MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC
-        name = 'SET_ROCKET_COORDINATES_ARP_TC'
-        fieldnames = ['latitude', 'longitude']
-        ordered_fieldnames = ['latitude', 'longitude']
-        fieldtypes = ['float', 'float']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"latitude": "deg", "longitude": "deg"}
-        format = '<ff'
-        native_format = bytearray('<ff', 'ascii')
-        orders = [0, 1]
-        lengths = [1, 1]
-        array_lengths = [0, 0]
-        crc_extra = 164
-        unpacker = struct.Struct('<ff')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, latitude, longitude):
-                MAVLink_message.__init__(self, MAVLink_set_rocket_coordinates_arp_tc_message.id, MAVLink_set_rocket_coordinates_arp_tc_message.name)
-                self._fieldnames = MAVLink_set_rocket_coordinates_arp_tc_message.fieldnames
-                self._instance_field = MAVLink_set_rocket_coordinates_arp_tc_message.instance_field
-                self._instance_offset = MAVLink_set_rocket_coordinates_arp_tc_message.instance_offset
-                self.latitude = latitude
-                self.longitude = longitude
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 164, struct.pack('<ff', self.latitude, self.longitude), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 22, struct.pack('<QfffffffffffffffffHHHHHHHHHHBBBBB', self.timestamp, self.yaw, self.pitch, self.roll, self.target_yaw, self.target_pitch, self.stepperX_pos, self.stepperX_delta, self.stepperX_speed, self.stepperY_pos, self.stepperY_delta, self.stepperY_speed, self.gps_latitude, self.gps_longitude, self.gps_height, self.main_rx_rssi, self.payload_rx_rssi, self.battery_voltage, self.main_packet_tx_error_count, self.main_tx_bitrate, self.main_packet_rx_success_count, self.main_packet_rx_drop_count, self.main_rx_bitrate, self.payload_packet_tx_error_count, self.payload_tx_bitrate, self.payload_packet_rx_success_count, self.payload_packet_rx_drop_count, self.payload_rx_bitrate, self.gps_fix, self.main_radio_present, self.payload_radio_present, self.ethernet_present, self.ethernet_status), force_mavlink1=force_mavlink1)
 
 class MAVLink_sys_tm_message(MAVLink_message):
         '''
@@ -2114,23 +2218,23 @@ class MAVLink_sys_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_SYS_TM
         name = 'SYS_TM'
-        fieldnames = ['timestamp', 'logger', 'event_broker', 'radio', 'pin_observer', 'sensors', 'board_scheduler']
-        ordered_fieldnames = ['timestamp', 'logger', 'event_broker', 'radio', 'pin_observer', 'sensors', 'board_scheduler']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
+        fieldnames = ['timestamp', 'logger', 'event_broker', 'radio', 'sensors', 'actuators', 'pin_handler', 'can_handler', 'scheduler']
+        ordered_fieldnames = ['timestamp', 'logger', 'event_broker', 'radio', 'sensors', 'actuators', 'pin_handler', 'can_handler', 'scheduler']
+        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
         fieldunits_by_name = {"timestamp": "us"}
-        format = '<QBBBBBB'
-        native_format = bytearray('<QBBBBBB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 5, 6]
-        lengths = [1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 183
-        unpacker = struct.Struct('<QBBBBBB')
+        format = '<QBBBBBBBB'
+        native_format = bytearray('<QBBBBBBBB', 'ascii')
+        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8]
+        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 48
+        unpacker = struct.Struct('<QBBBBBBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, logger, event_broker, radio, pin_observer, sensors, board_scheduler):
+        def __init__(self, timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler):
                 MAVLink_message.__init__(self, MAVLink_sys_tm_message.id, MAVLink_sys_tm_message.name)
                 self._fieldnames = MAVLink_sys_tm_message.fieldnames
                 self._instance_field = MAVLink_sys_tm_message.instance_field
@@ -2139,50 +2243,14 @@ class MAVLink_sys_tm_message(MAVLink_message):
                 self.logger = logger
                 self.event_broker = event_broker
                 self.radio = radio
-                self.pin_observer = pin_observer
                 self.sensors = sensors
-                self.board_scheduler = board_scheduler
-
-        def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 183, struct.pack('<QBBBBBB', self.timestamp, self.logger, self.event_broker, self.radio, self.pin_observer, self.sensors, self.board_scheduler), force_mavlink1=force_mavlink1)
-
-class MAVLink_fsm_tm_message(MAVLink_message):
-        '''
-        Flight State Machine status telemetry
-        '''
-        id = MAVLINK_MSG_ID_FSM_TM
-        name = 'FSM_TM'
-        fieldnames = ['timestamp', 'ada_state', 'abk_state', 'dpl_state', 'fmm_state', 'nas_state', 'wes_state']
-        ordered_fieldnames = ['timestamp', 'ada_state', 'abk_state', 'dpl_state', 'fmm_state', 'nas_state', 'wes_state']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
-        fielddisplays_by_name = {}
-        fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us"}
-        format = '<QBBBBBB'
-        native_format = bytearray('<QBBBBBB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 5, 6]
-        lengths = [1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 242
-        unpacker = struct.Struct('<QBBBBBB')
-        instance_field = None
-        instance_offset = -1
-
-        def __init__(self, timestamp, ada_state, abk_state, dpl_state, fmm_state, nas_state, wes_state):
-                MAVLink_message.__init__(self, MAVLink_fsm_tm_message.id, MAVLink_fsm_tm_message.name)
-                self._fieldnames = MAVLink_fsm_tm_message.fieldnames
-                self._instance_field = MAVLink_fsm_tm_message.instance_field
-                self._instance_offset = MAVLink_fsm_tm_message.instance_offset
-                self.timestamp = timestamp
-                self.ada_state = ada_state
-                self.abk_state = abk_state
-                self.dpl_state = dpl_state
-                self.fmm_state = fmm_state
-                self.nas_state = nas_state
-                self.wes_state = wes_state
+                self.actuators = actuators
+                self.pin_handler = pin_handler
+                self.can_handler = can_handler
+                self.scheduler = scheduler
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 242, struct.pack('<QBBBBBB', self.timestamp, self.ada_state, self.abk_state, self.dpl_state, self.fmm_state, self.nas_state, self.wes_state), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 48, struct.pack('<QBBBBBBBB', self.timestamp, self.logger, self.event_broker, self.radio, self.sensors, self.actuators, self.pin_handler, self.can_handler, self.scheduler), force_mavlink1=force_mavlink1)
 
 class MAVLink_logger_tm_message(MAVLink_message):
         '''
@@ -2228,7 +2296,7 @@ class MAVLink_logger_tm_message(MAVLink_message):
 
 class MAVLink_mavlink_stats_tm_message(MAVLink_message):
         '''
-        Status of the TMTCManager telemetry
+        Status of MavlinkDriver
         '''
         id = MAVLINK_MSG_ID_MAVLINK_STATS_TM
         name = 'MAVLINK_STATS_TM'
@@ -2270,29 +2338,64 @@ class MAVLink_mavlink_stats_tm_message(MAVLink_message):
         def pack(self, mav, force_mavlink1=False):
                 return MAVLink_message.pack(self, mav, 108, struct.pack('<QIHHHHHBBBBBB', self.timestamp, self.parse_state, self.n_send_queue, self.max_send_queue, self.n_send_errors, self.packet_rx_success_count, self.packet_rx_drop_count, self.msg_received, self.buffer_overrun, self.parse_error, self.packet_idx, self.current_rx_seq, self.current_tx_seq), force_mavlink1=force_mavlink1)
 
+class MAVLink_can_stats_tm_message(MAVLink_message):
+        '''
+        Status of CanHandler
+        '''
+        id = MAVLINK_MSG_ID_CAN_STATS_TM
+        name = 'CAN_STATS_TM'
+        fieldnames = ['timestamp', 'payload_bit_rate', 'total_bit_rate', 'load_percent']
+        ordered_fieldnames = ['timestamp', 'payload_bit_rate', 'total_bit_rate', 'load_percent']
+        fieldtypes = ['uint64_t', 'float', 'float', 'float']
+        fielddisplays_by_name = {}
+        fieldenums_by_name = {}
+        fieldunits_by_name = {"timestamp": "us"}
+        format = '<Qfff'
+        native_format = bytearray('<Qfff', 'ascii')
+        orders = [0, 1, 2, 3]
+        lengths = [1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0]
+        crc_extra = 39
+        unpacker = struct.Struct('<Qfff')
+        instance_field = None
+        instance_offset = -1
+
+        def __init__(self, timestamp, payload_bit_rate, total_bit_rate, load_percent):
+                MAVLink_message.__init__(self, MAVLink_can_stats_tm_message.id, MAVLink_can_stats_tm_message.name)
+                self._fieldnames = MAVLink_can_stats_tm_message.fieldnames
+                self._instance_field = MAVLink_can_stats_tm_message.instance_field
+                self._instance_offset = MAVLink_can_stats_tm_message.instance_offset
+                self.timestamp = timestamp
+                self.payload_bit_rate = payload_bit_rate
+                self.total_bit_rate = total_bit_rate
+                self.load_percent = load_percent
+
+        def pack(self, mav, force_mavlink1=False):
+                return MAVLink_message.pack(self, mav, 39, struct.pack('<Qfff', self.timestamp, self.payload_bit_rate, self.total_bit_rate, self.load_percent), force_mavlink1=force_mavlink1)
+
 class MAVLink_task_stats_tm_message(MAVLink_message):
         '''
         Statistics of the Task Scheduler
         '''
         id = MAVLINK_MSG_ID_TASK_STATS_TM
         name = 'TASK_STATS_TM'
-        fieldnames = ['timestamp', 'task_id', 'task_period', 'task_min', 'task_max', 'task_mean', 'task_stddev']
-        ordered_fieldnames = ['timestamp', 'task_min', 'task_max', 'task_mean', 'task_stddev', 'task_period', 'task_id']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint16_t', 'float', 'float', 'float', 'float']
+        fieldnames = ['timestamp', 'task_id', 'task_period', 'task_missed_events', 'task_failed_events', 'task_activation_mean', 'task_activation_stddev', 'task_period_mean', 'task_period_stddev', 'task_workload_mean', 'task_workload_stddev']
+        ordered_fieldnames = ['timestamp', 'task_missed_events', 'task_failed_events', 'task_activation_mean', 'task_activation_stddev', 'task_period_mean', 'task_period_stddev', 'task_workload_mean', 'task_workload_stddev', 'task_id', 'task_period']
+        fieldtypes = ['uint64_t', 'uint16_t', 'uint16_t', 'uint32_t', 'uint32_t', 'float', 'float', 'float', 'float', 'float', 'float']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "task_period": "ms"}
-        format = '<QffffHB'
-        native_format = bytearray('<QffffHB', 'ascii')
-        orders = [0, 6, 5, 1, 2, 3, 4]
-        lengths = [1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 133
-        unpacker = struct.Struct('<QffffHB')
+        fieldunits_by_name = {"timestamp": "us", "task_period": "ns"}
+        format = '<QIIffffffHH'
+        native_format = bytearray('<QIIffffffHH', 'ascii')
+        orders = [0, 9, 10, 1, 2, 3, 4, 5, 6, 7, 8]
+        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 19
+        unpacker = struct.Struct('<QIIffffffHH')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, task_id, task_period, task_min, task_max, task_mean, task_stddev):
+        def __init__(self, timestamp, task_id, task_period, task_missed_events, task_failed_events, task_activation_mean, task_activation_stddev, task_period_mean, task_period_stddev, task_workload_mean, task_workload_stddev):
                 MAVLink_message.__init__(self, MAVLink_task_stats_tm_message.id, MAVLink_task_stats_tm_message.name)
                 self._fieldnames = MAVLink_task_stats_tm_message.fieldnames
                 self._instance_field = MAVLink_task_stats_tm_message.instance_field
@@ -2300,13 +2403,17 @@ class MAVLink_task_stats_tm_message(MAVLink_message):
                 self.timestamp = timestamp
                 self.task_id = task_id
                 self.task_period = task_period
-                self.task_min = task_min
-                self.task_max = task_max
-                self.task_mean = task_mean
-                self.task_stddev = task_stddev
+                self.task_missed_events = task_missed_events
+                self.task_failed_events = task_failed_events
+                self.task_activation_mean = task_activation_mean
+                self.task_activation_stddev = task_activation_stddev
+                self.task_period_mean = task_period_mean
+                self.task_period_stddev = task_period_stddev
+                self.task_workload_mean = task_workload_mean
+                self.task_workload_stddev = task_workload_stddev
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 133, struct.pack('<QffffHB', self.timestamp, self.task_min, self.task_max, self.task_mean, self.task_stddev, self.task_period, self.task_id), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 19, struct.pack('<QIIffffffHH', self.timestamp, self.task_missed_events, self.task_failed_events, self.task_activation_mean, self.task_activation_stddev, self.task_period_mean, self.task_period_stddev, self.task_workload_mean, self.task_workload_stddev, self.task_id, self.task_period), force_mavlink1=force_mavlink1)
 
 class MAVLink_ada_tm_message(MAVLink_message):
         '''
@@ -2413,7 +2520,7 @@ class MAVLink_mea_tm_message(MAVLink_message):
         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"}
+        fieldunits_by_name = {"timestamp": "us", "mass": "kg", "corrected_pressure": "Pa"}
         format = '<QfffffB'
         native_format = bytearray('<QfffffB', 'ascii')
         orders = [0, 6, 1, 2, 3, 4, 5]
@@ -2446,23 +2553,23 @@ class MAVLink_rocket_flight_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM
         name = 'ROCKET_FLIGHT_TM'
-        fieldnames = ['timestamp', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'pin_quick_connector', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'temperature', 'logger_error']
-        ordered_fieldnames = ['timestamp', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'pin_quick_connector', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'temperature', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'gps_fix', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'logger_error']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'int8_t']
+        fieldnames = ['timestamp', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'battery_voltage', 'cam_battery_voltage', 'temperature']
+        ordered_fieldnames = ['timestamp', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'battery_voltage', 'cam_battery_voltage', 'temperature', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'gps_fix', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence']
+        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']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "pressure_ada": "Pa", "pressure_digi": "Pa", "pressure_static": "Pa", "pressure_dpl": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "ada_vert_speed": "m/s", "mea_mass": "kg", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "abk_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "battery_voltage": "V", "cam_battery_voltage": "V", "current_consumption": "A", "temperature": "degC"}
-        format = '<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb'
-        native_format = bytearray('<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb', 'ascii')
-        orders = [0, 40, 41, 42, 43, 44, 45, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 46, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 47, 48, 49, 50, 36, 37, 38, 39, 51]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 214
-        unpacker = struct.Struct('<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb')
+        fieldunits_by_name = {"timestamp": "us", "pressure_ada": "Pa", "pressure_digi": "Pa", "pressure_static": "Pa", "pressure_dpl": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "ada_vert_speed": "m/s", "mea_mass": "kg", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "abk_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "battery_voltage": "V", "cam_battery_voltage": "V", "temperature": "degC"}
+        format = '<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBB'
+        native_format = bytearray('<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBB', '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]
+        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]
+        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]
+        crc_extra = 52
+        unpacker = struct.Struct('<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error):
+        def __init__(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, temperature):
                 MAVLink_message.__init__(self, MAVLink_rocket_flight_tm_message.id, MAVLink_rocket_flight_tm_message.name)
                 self._fieldnames = MAVLink_rocket_flight_tm_message.fieldnames
                 self._instance_field = MAVLink_rocket_flight_tm_message.instance_field
@@ -2509,19 +2616,16 @@ class MAVLink_rocket_flight_tm_message(MAVLink_message):
                 self.nas_bias_x = nas_bias_x
                 self.nas_bias_y = nas_bias_y
                 self.nas_bias_z = nas_bias_z
-                self.pin_quick_connector = pin_quick_connector
                 self.pin_launch = pin_launch
                 self.pin_nosecone = pin_nosecone
                 self.pin_expulsion = pin_expulsion
                 self.cutter_presence = cutter_presence
                 self.battery_voltage = battery_voltage
                 self.cam_battery_voltage = cam_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, 214, struct.pack('<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb', self.timestamp, self.pressure_ada, self.pressure_digi, self.pressure_static, self.pressure_dpl, self.airspeed_pitot, self.altitude_agl, self.ada_vert_speed, self.mea_mass, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.abk_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.pin_quick_connector, self.battery_voltage, self.cam_battery_voltage, self.current_consumption, self.temperature, self.ada_state, self.fmm_state, self.dpl_state, self.abk_state, self.nas_state, self.mea_state, self.gps_fix, self.pin_launch, self.pin_nosecone, self.pin_expulsion, self.cutter_presence, self.logger_error), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 52, struct.pack('<QfffffffffffffffffffffffffffffffffffffBBBBBBBBBBB', self.timestamp, self.pressure_ada, self.pressure_digi, self.pressure_static, self.pressure_dpl, self.airspeed_pitot, self.altitude_agl, self.ada_vert_speed, self.mea_mass, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.abk_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.battery_voltage, self.cam_battery_voltage, self.temperature, self.ada_state, self.fmm_state, self.dpl_state, self.abk_state, self.nas_state, self.mea_state, self.gps_fix, self.pin_launch, self.pin_nosecone, self.pin_expulsion, self.cutter_presence), force_mavlink1=force_mavlink1)
 
 class MAVLink_payload_flight_tm_message(MAVLink_message):
         '''
@@ -2529,23 +2633,23 @@ class MAVLink_payload_flight_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM
         name = 'PAYLOAD_FLIGHT_TM'
-        fieldnames = ['timestamp', 'fmm_state', 'nas_state', 'wes_state', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'pin_nosecone', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'cutter_presence', 'temperature', 'logger_error']
-        ordered_fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'temperature', 'fmm_state', 'nas_state', 'wes_state', 'gps_fix', 'pin_nosecone', 'cutter_presence', 'logger_error']
-        fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'uint8_t', 'float', 'int8_t']
+        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_launch', 'pin_nosecone', 'cutter_presence', 'battery_voltage', 'cam_battery_voltage', 'temperature']
+        ordered_fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'battery_voltage', 'cam_battery_voltage', 'temperature', 'fmm_state', 'nas_state', 'wes_state', 'gps_fix', 'pin_launch', 'pin_nosecone', 'cutter_presence']
+        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', 'uint8_t', 'uint8_t', 'float', 'float', 'float']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "pressure_digi": "Pa", "pressure_static": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "left_servo_angle": "deg", "right_servo_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "wes_n": "m/s", "wes_e": "m/s", "battery_voltage": "V", "cam_battery_voltage": "V", "current_consumption": "A", "temperature": "degC"}
-        format = '<QfffffffffffffffffffffffffffffffffffffBBBBBBb'
-        native_format = bytearray('<QfffffffffffffffffffffffffffffffffffffBBBBBBb', 'ascii')
-        orders = [0, 38, 39, 40, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 41, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 42, 34, 35, 36, 43, 37, 44]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 84
-        unpacker = struct.Struct('<QfffffffffffffffffffffffffffffffffffffBBBBBBb')
+        fieldunits_by_name = {"timestamp": "us", "pressure_digi": "Pa", "pressure_static": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "left_servo_angle": "deg", "right_servo_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "wes_n": "m/s", "wes_e": "m/s", "battery_voltage": "V", "cam_battery_voltage": "V", "temperature": "degC"}
+        format = '<QffffffffffffffffffffffffffffffffffffBBBBBBB'
+        native_format = bytearray('<QffffffffffffffffffffffffffffffffffffBBBBBBB', '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, 42, 43, 34, 35, 36]
+        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 = 59
+        unpacker = struct.Struct('<QffffffffffffffffffffffffffffffffffffBBBBBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, 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_launch, pin_nosecone, cutter_presence, battery_voltage, cam_battery_voltage, temperature):
                 MAVLink_message.__init__(self, MAVLink_payload_flight_tm_message.id, MAVLink_payload_flight_tm_message.name)
                 self._fieldnames = MAVLink_payload_flight_tm_message.fieldnames
                 self._instance_field = MAVLink_payload_flight_tm_message.instance_field
@@ -2588,16 +2692,15 @@ class MAVLink_payload_flight_tm_message(MAVLink_message):
                 self.nas_bias_z = nas_bias_z
                 self.wes_n = wes_n
                 self.wes_e = wes_e
+                self.pin_launch = pin_launch
                 self.pin_nosecone = pin_nosecone
+                self.cutter_presence = cutter_presence
                 self.battery_voltage = battery_voltage
                 self.cam_battery_voltage = cam_battery_voltage
-                self.current_consumption = current_consumption
-                self.cutter_presence = cutter_presence
                 self.temperature = temperature
-                self.logger_error = logger_error
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 84, struct.pack('<QfffffffffffffffffffffffffffffffffffffBBBBBBb', self.timestamp, self.pressure_digi, self.pressure_static, self.airspeed_pitot, self.altitude_agl, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.left_servo_angle, self.right_servo_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.wes_n, self.wes_e, self.battery_voltage, self.cam_battery_voltage, self.current_consumption, self.temperature, self.fmm_state, self.nas_state, self.wes_state, self.gps_fix, self.pin_nosecone, self.cutter_presence, self.logger_error), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 59, struct.pack('<QffffffffffffffffffffffffffffffffffffBBBBBBB', self.timestamp, self.pressure_digi, self.pressure_static, self.airspeed_pitot, self.altitude_agl, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.left_servo_angle, self.right_servo_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.wes_n, self.wes_e, self.battery_voltage, self.cam_battery_voltage, self.temperature, self.fmm_state, self.nas_state, self.wes_state, self.gps_fix, self.pin_launch, self.pin_nosecone, self.cutter_presence), force_mavlink1=force_mavlink1)
 
 class MAVLink_rocket_stats_tm_message(MAVLink_message):
         '''
@@ -2605,23 +2708,23 @@ class MAVLink_rocket_stats_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_ROCKET_STATS_TM
         name = 'ROCKET_STATS_TM'
-        fieldnames = ['liftoff_ts', 'liftoff_max_acc_ts', 'liftoff_max_acc', 'dpl_ts', 'dpl_max_acc', 'max_z_speed_ts', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'ada_min_pressure', 'dpl_vane_max_pressure', 'cpu_load', 'free_heap']
-        ordered_fieldnames = ['liftoff_ts', 'liftoff_max_acc_ts', 'dpl_ts', 'max_z_speed_ts', 'apogee_ts', 'liftoff_max_acc', 'dpl_max_acc', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'ada_min_pressure', 'dpl_vane_max_pressure', 'cpu_load', 'free_heap']
-        fieldtypes = ['uint64_t', 'uint64_t', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint32_t']
+        fieldnames = ['liftoff_ts', 'liftoff_max_acc_ts', 'liftoff_max_acc', 'dpl_ts', 'dpl_max_acc', 'max_z_speed_ts', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'ada_min_pressure', 'dpl_bay_max_pressure', 'cpu_load', 'free_heap', 'log_number', 'log_good', 'payload_board_state', 'motor_board_state', 'payload_can_status', 'motor_can_status', 'rig_can_status', 'hil_state']
+        ordered_fieldnames = ['liftoff_ts', 'liftoff_max_acc_ts', 'dpl_ts', 'max_z_speed_ts', 'apogee_ts', 'liftoff_max_acc', 'dpl_max_acc', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'ada_min_pressure', 'dpl_bay_max_pressure', 'cpu_load', 'free_heap', 'log_good', 'log_number', 'payload_board_state', 'motor_board_state', 'payload_can_status', 'motor_can_status', 'rig_can_status', 'hil_state']
+        fieldtypes = ['uint64_t', 'uint64_t', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint32_t', 'int16_t', 'int32_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"liftoff_ts": "us", "liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "dpl_ts": "us", "dpl_max_acc": "m/s2", "max_z_speed_ts": "us", "max_z_speed": "m/s", "max_airspeed_pitot": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "min_pressure": "Pa", "ada_min_pressure": "Pa", "dpl_vane_max_pressure": "Pa"}
-        format = '<QQQQQffffffffffffI'
-        native_format = bytearray('<QQQQQffffffffffffI', 'ascii')
-        orders = [0, 1, 5, 2, 6, 3, 7, 8, 9, 4, 10, 11, 12, 13, 14, 15, 16, 17]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 245
-        unpacker = struct.Struct('<QQQQQffffffffffffI')
+        fieldunits_by_name = {"liftoff_ts": "us", "liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "dpl_ts": "us", "dpl_max_acc": "m/s2", "max_z_speed_ts": "us", "max_z_speed": "m/s", "max_airspeed_pitot": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "min_pressure": "Pa", "ada_min_pressure": "Pa", "dpl_bay_max_pressure": "Pa"}
+        format = '<QQQQQffffffffffffIihBBBBBB'
+        native_format = bytearray('<QQQQQffffffffffffIihBBBBBB', 'ascii')
+        orders = [0, 1, 5, 2, 6, 3, 7, 8, 9, 4, 10, 11, 12, 13, 14, 15, 16, 17, 19, 18, 20, 21, 22, 23, 24, 25]
+        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]
+        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]
+        crc_extra = 46
+        unpacker = struct.Struct('<QQQQQffffffffffffIihBBBBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_vane_max_pressure, cpu_load, free_heap):
+        def __init__(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_bay_max_pressure, cpu_load, free_heap, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, hil_state):
                 MAVLink_message.__init__(self, MAVLink_rocket_stats_tm_message.id, MAVLink_rocket_stats_tm_message.name)
                 self._fieldnames = MAVLink_rocket_stats_tm_message.fieldnames
                 self._instance_field = MAVLink_rocket_stats_tm_message.instance_field
@@ -2641,12 +2744,20 @@ class MAVLink_rocket_stats_tm_message(MAVLink_message):
                 self.apogee_alt = apogee_alt
                 self.min_pressure = min_pressure
                 self.ada_min_pressure = ada_min_pressure
-                self.dpl_vane_max_pressure = dpl_vane_max_pressure
+                self.dpl_bay_max_pressure = dpl_bay_max_pressure
                 self.cpu_load = cpu_load
                 self.free_heap = free_heap
+                self.log_number = log_number
+                self.log_good = log_good
+                self.payload_board_state = payload_board_state
+                self.motor_board_state = motor_board_state
+                self.payload_can_status = payload_can_status
+                self.motor_can_status = motor_can_status
+                self.rig_can_status = rig_can_status
+                self.hil_state = hil_state
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 245, struct.pack('<QQQQQffffffffffffI', self.liftoff_ts, self.liftoff_max_acc_ts, self.dpl_ts, self.max_z_speed_ts, self.apogee_ts, self.liftoff_max_acc, self.dpl_max_acc, self.max_z_speed, self.max_airspeed_pitot, self.max_speed_altitude, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.min_pressure, self.ada_min_pressure, self.dpl_vane_max_pressure, self.cpu_load, self.free_heap), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 46, struct.pack('<QQQQQffffffffffffIihBBBBBB', self.liftoff_ts, self.liftoff_max_acc_ts, self.dpl_ts, self.max_z_speed_ts, self.apogee_ts, self.liftoff_max_acc, self.dpl_max_acc, self.max_z_speed, self.max_airspeed_pitot, self.max_speed_altitude, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.min_pressure, self.ada_min_pressure, self.dpl_bay_max_pressure, self.cpu_load, self.free_heap, self.log_good, self.log_number, self.payload_board_state, self.motor_board_state, self.payload_can_status, self.motor_can_status, self.rig_can_status, self.hil_state), force_mavlink1=force_mavlink1)
 
 class MAVLink_payload_stats_tm_message(MAVLink_message):
         '''
@@ -2654,23 +2765,23 @@ class MAVLink_payload_stats_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_PAYLOAD_STATS_TM
         name = 'PAYLOAD_STATS_TM'
-        fieldnames = ['liftoff_max_acc_ts', 'liftoff_max_acc', 'dpl_ts', 'dpl_max_acc', 'max_z_speed_ts', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'cpu_load', 'free_heap']
-        ordered_fieldnames = ['liftoff_max_acc_ts', 'dpl_ts', 'max_z_speed_ts', 'apogee_ts', 'liftoff_max_acc', 'dpl_max_acc', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'cpu_load', 'free_heap']
-        fieldtypes = ['uint64_t', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'uint32_t']
+        fieldnames = ['liftoff_max_acc_ts', 'liftoff_max_acc', 'dpl_ts', 'dpl_max_acc', 'max_z_speed_ts', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'cpu_load', 'free_heap', 'log_number', 'log_good', 'main_board_state', 'motor_board_state', 'main_can_status', 'motor_can_status', 'rig_can_status', 'hil_state']
+        ordered_fieldnames = ['liftoff_max_acc_ts', 'dpl_ts', 'max_z_speed_ts', 'apogee_ts', 'liftoff_max_acc', 'dpl_max_acc', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'cpu_load', 'free_heap', 'log_good', 'log_number', 'main_board_state', 'motor_board_state', 'main_can_status', 'motor_can_status', 'rig_can_status', 'hil_state']
+        fieldtypes = ['uint64_t', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'uint32_t', 'int16_t', 'int32_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
         fieldunits_by_name = {"liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "dpl_ts": "us", "dpl_max_acc": "m/s2", "max_z_speed_ts": "us", "max_z_speed": "m/s", "max_airspeed_pitot": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "min_pressure": "Pa"}
-        format = '<QQQQffffffffffI'
-        native_format = bytearray('<QQQQffffffffffI', 'ascii')
-        orders = [0, 4, 1, 5, 2, 6, 7, 8, 3, 9, 10, 11, 12, 13, 14]
-        lengths = [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]
-        crc_extra = 115
-        unpacker = struct.Struct('<QQQQffffffffffI')
+        format = '<QQQQffffffffffIihBBBBBB'
+        native_format = bytearray('<QQQQffffffffffIihBBBBBB', 'ascii')
+        orders = [0, 4, 1, 5, 2, 6, 7, 8, 3, 9, 10, 11, 12, 13, 14, 16, 15, 17, 18, 19, 20, 21, 22]
+        lengths = [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]
+        crc_extra = 64
+        unpacker = struct.Struct('<QQQQffffffffffIihBBBBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap):
+        def __init__(self, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state):
                 MAVLink_message.__init__(self, MAVLink_payload_stats_tm_message.id, MAVLink_payload_stats_tm_message.name)
                 self._fieldnames = MAVLink_payload_stats_tm_message.fieldnames
                 self._instance_field = MAVLink_payload_stats_tm_message.instance_field
@@ -2690,9 +2801,17 @@ class MAVLink_payload_stats_tm_message(MAVLink_message):
                 self.min_pressure = min_pressure
                 self.cpu_load = cpu_load
                 self.free_heap = free_heap
+                self.log_number = log_number
+                self.log_good = log_good
+                self.main_board_state = main_board_state
+                self.motor_board_state = motor_board_state
+                self.main_can_status = main_can_status
+                self.motor_can_status = motor_can_status
+                self.rig_can_status = rig_can_status
+                self.hil_state = hil_state
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 115, struct.pack('<QQQQffffffffffI', self.liftoff_max_acc_ts, self.dpl_ts, self.max_z_speed_ts, self.apogee_ts, self.liftoff_max_acc, self.dpl_max_acc, self.max_z_speed, self.max_airspeed_pitot, self.max_speed_altitude, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.min_pressure, self.cpu_load, self.free_heap), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 64, struct.pack('<QQQQffffffffffIihBBBBBB', self.liftoff_max_acc_ts, self.dpl_ts, self.max_z_speed_ts, self.apogee_ts, self.liftoff_max_acc, self.dpl_max_acc, self.max_z_speed, self.max_airspeed_pitot, self.max_speed_altitude, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.min_pressure, self.cpu_load, self.free_heap, self.log_good, self.log_number, self.main_board_state, self.motor_board_state, self.main_can_status, self.motor_can_status, self.rig_can_status, self.hil_state), force_mavlink1=force_mavlink1)
 
 class MAVLink_gse_tm_message(MAVLink_message):
         '''
@@ -2700,23 +2819,23 @@ class MAVLink_gse_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_GSE_TM
         name = 'GSE_TM'
-        fieldnames = ['timestamp', 'loadcell_rocket', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'arming_state', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'nitrogen_valve_state', 'gmm_state', 'tars_state', 'battery_voltage', 'current_consumption', 'main_board_status', 'payload_board_status', 'motor_board_status']
-        ordered_fieldnames = ['timestamp', 'loadcell_rocket', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'battery_voltage', 'current_consumption', 'arming_state', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'nitrogen_valve_state', 'gmm_state', 'tars_state', 'main_board_status', 'payload_board_status', 'motor_board_status']
-        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t']
+        fieldnames = ['timestamp', 'loadcell_rocket', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'nitrogen_valve_state', 'gmm_state', 'tars_state', 'arming_state', 'battery_voltage', 'current_consumption', 'umbilical_current_consumption', 'main_board_state', 'payload_board_state', 'motor_board_state', 'main_can_status', 'payload_can_status', 'motor_can_status', 'log_number', 'log_good']
+        ordered_fieldnames = ['timestamp', 'loadcell_rocket', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'battery_voltage', 'current_consumption', 'umbilical_current_consumption', 'log_good', 'log_number', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'nitrogen_valve_state', 'gmm_state', 'tars_state', 'arming_state', 'main_board_state', 'payload_board_state', 'motor_board_state', 'main_can_status', 'payload_can_status', 'motor_can_status']
+        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'int16_t', 'int32_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "loadcell_rocket": "kg", "loadcell_vessel": "kg", "filling_pressure": "Bar", "vessel_pressure": "Bar"}
-        format = '<QffffffBBBBBBBBBBB'
-        native_format = bytearray('<QffffffBBBBBBBBBBB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 7, 8, 9, 10, 11, 12, 13, 14, 5, 6, 15, 16, 17]
-        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
-        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 81
-        unpacker = struct.Struct('<QffffffBBBBBBBBBBB')
+        fieldunits_by_name = {"timestamp": "us", "loadcell_rocket": "kg", "loadcell_vessel": "kg", "filling_pressure": "Bar", "vessel_pressure": "Bar", "current_consumption": "A", "umbilical_current_consumption": "A"}
+        format = '<QfffffffihBBBBBBBBBBBBBB'
+        native_format = bytearray('<QfffffffihBBBBBBBBBBBBBB', 'ascii')
+        orders = [0, 1, 2, 3, 4, 10, 11, 12, 13, 14, 15, 16, 17, 5, 6, 7, 18, 19, 20, 21, 22, 23, 9, 8]
+        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 33
+        unpacker = struct.Struct('<QfffffffihBBBBBBBBBBBBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status):
+        def __init__(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, arming_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good):
                 MAVLink_message.__init__(self, MAVLink_gse_tm_message.id, MAVLink_gse_tm_message.name)
                 self._fieldnames = MAVLink_gse_tm_message.fieldnames
                 self._instance_field = MAVLink_gse_tm_message.instance_field
@@ -2726,7 +2845,6 @@ class MAVLink_gse_tm_message(MAVLink_message):
                 self.loadcell_vessel = loadcell_vessel
                 self.filling_pressure = filling_pressure
                 self.vessel_pressure = vessel_pressure
-                self.arming_state = arming_state
                 self.filling_valve_state = filling_valve_state
                 self.venting_valve_state = venting_valve_state
                 self.release_valve_state = release_valve_state
@@ -2734,14 +2852,21 @@ class MAVLink_gse_tm_message(MAVLink_message):
                 self.nitrogen_valve_state = nitrogen_valve_state
                 self.gmm_state = gmm_state
                 self.tars_state = tars_state
+                self.arming_state = arming_state
                 self.battery_voltage = battery_voltage
                 self.current_consumption = current_consumption
-                self.main_board_status = main_board_status
-                self.payload_board_status = payload_board_status
-                self.motor_board_status = motor_board_status
+                self.umbilical_current_consumption = umbilical_current_consumption
+                self.main_board_state = main_board_state
+                self.payload_board_state = payload_board_state
+                self.motor_board_state = motor_board_state
+                self.main_can_status = main_can_status
+                self.payload_can_status = payload_can_status
+                self.motor_can_status = motor_can_status
+                self.log_number = log_number
+                self.log_good = log_good
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 81, struct.pack('<QffffffBBBBBBBBBBB', self.timestamp, self.loadcell_rocket, self.loadcell_vessel, self.filling_pressure, self.vessel_pressure, self.battery_voltage, self.current_consumption, self.arming_state, self.filling_valve_state, self.venting_valve_state, self.release_valve_state, self.main_valve_state, self.nitrogen_valve_state, self.gmm_state, self.tars_state, self.main_board_status, self.payload_board_status, self.motor_board_status), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 33, struct.pack('<QfffffffihBBBBBBBBBBBBBB', self.timestamp, self.loadcell_rocket, self.loadcell_vessel, self.filling_pressure, self.vessel_pressure, self.battery_voltage, self.current_consumption, self.umbilical_current_consumption, self.log_good, self.log_number, self.filling_valve_state, self.venting_valve_state, self.release_valve_state, self.main_valve_state, self.nitrogen_valve_state, self.gmm_state, self.tars_state, self.arming_state, self.main_board_state, self.payload_board_state, self.motor_board_state, self.main_can_status, self.payload_can_status, self.motor_can_status), force_mavlink1=force_mavlink1)
 
 class MAVLink_motor_tm_message(MAVLink_message):
         '''
@@ -2749,23 +2874,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', 'tank_temperature', 'main_valve_state', 'venting_valve_state', 'battery_voltage', 'current_consumption']
-        ordered_fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'tank_temperature', 'battery_voltage', 'current_consumption', 'main_valve_state', 'venting_valve_state']
-        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'float', 'float']
+        fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'tank_temperature', 'main_valve_state', 'venting_valve_state', 'battery_voltage', 'log_number', 'log_good', 'hil_state']
+        ordered_fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'tank_temperature', 'battery_voltage', 'log_good', 'log_number', 'main_valve_state', 'venting_valve_state', 'hil_state']
+        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'float', 'int16_t', 'int32_t', 'uint8_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "top_tank_pressure": "Bar", "bottom_tank_pressure": "Bar", "combustion_chamber_pressure": "Bar", "battery_voltage": "V", "current_consumption": "A"}
-        format = '<QffffffBB'
-        native_format = bytearray('<QffffffBB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 7, 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 = 89
-        unpacker = struct.Struct('<QffffffBB')
+        fieldunits_by_name = {"timestamp": "us", "top_tank_pressure": "Bar", "bottom_tank_pressure": "Bar", "combustion_chamber_pressure": "Bar", "battery_voltage": "V"}
+        format = '<QfffffihBBB'
+        native_format = bytearray('<QfffffihBBB', 'ascii')
+        orders = [0, 1, 2, 3, 4, 8, 9, 5, 7, 6, 10]
+        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 67
+        unpacker = struct.Struct('<QfffffihBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, current_consumption):
+        def __init__(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, log_good, hil_state):
                 MAVLink_message.__init__(self, MAVLink_motor_tm_message.id, MAVLink_motor_tm_message.name)
                 self._fieldnames = MAVLink_motor_tm_message.fieldnames
                 self._instance_field = MAVLink_motor_tm_message.instance_field
@@ -2778,10 +2903,12 @@ class MAVLink_motor_tm_message(MAVLink_message):
                 self.main_valve_state = main_valve_state
                 self.venting_valve_state = venting_valve_state
                 self.battery_voltage = battery_voltage
-                self.current_consumption = current_consumption
+                self.log_number = log_number
+                self.log_good = log_good
+                self.hil_state = hil_state
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 89, 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.main_valve_state, self.venting_valve_state), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 67, struct.pack('<QfffffihBBB', self.timestamp, self.top_tank_pressure, self.bottom_tank_pressure, self.combustion_chamber_pressure, self.tank_temperature, self.battery_voltage, self.log_good, self.log_number, self.main_valve_state, self.venting_valve_state, self.hil_state), force_mavlink1=force_mavlink1)
 
 
 mavlink_map = {
@@ -2791,11 +2918,12 @@ mavlink_map = {
         MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC : MAVLink_sensor_tm_request_tc_message,
         MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC : MAVLink_servo_tm_request_tc_message,
         MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC : MAVLink_set_servo_angle_tc_message,
-        MAVLINK_MSG_ID_WIGGLE_SERVO_TC : MAVLink_wiggle_servo_tc_message,
         MAVLINK_MSG_ID_RESET_SERVO_TC : MAVLink_reset_servo_tc_message,
+        MAVLINK_MSG_ID_WIGGLE_SERVO_TC : MAVLink_wiggle_servo_tc_message,
         MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC : MAVLink_set_reference_altitude_tc_message,
         MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC : MAVLink_set_reference_temperature_tc_message,
         MAVLINK_MSG_ID_SET_ORIENTATION_TC : MAVLink_set_orientation_tc_message,
+        MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC : MAVLink_set_orientation_quat_tc_message,
         MAVLINK_MSG_ID_SET_COORDINATES_TC : MAVLink_set_coordinates_tc_message,
         MAVLINK_MSG_ID_RAW_EVENT_TC : MAVLink_raw_event_tc_message,
         MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC : MAVLink_set_deployment_altitude_tc_message,
@@ -2805,12 +2933,17 @@ mavlink_map = {
         MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC : MAVLink_set_valve_maximum_aperture_tc_message,
         MAVLINK_MSG_ID_CONRIG_STATE_TC : MAVLink_conrig_state_tc_message,
         MAVLINK_MSG_ID_SET_IGNITION_TIME_TC : MAVLink_set_ignition_time_tc_message,
-        MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC : MAVLink_set_stepper_angle_tc_message,
-        MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC : MAVLink_set_stepper_steps_tc_message,
         MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC : MAVLink_set_nitrogen_time_tc_message,
         MAVLINK_MSG_ID_SET_COOLING_TIME_TC : MAVLink_set_cooling_time_tc_message,
+        MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC : MAVLink_set_stepper_angle_tc_message,
+        MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC : MAVLink_set_stepper_steps_tc_message,
+        MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC : MAVLink_set_stepper_multiplier_tc_message,
+        MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC : MAVLink_set_antenna_coordinates_arp_tc_message,
+        MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC : MAVLink_set_rocket_coordinates_arp_tc_message,
+        MAVLINK_MSG_ID_ARP_COMMAND_TC : MAVLink_arp_command_tc_message,
         MAVLINK_MSG_ID_ACK_TM : MAVLink_ack_tm_message,
         MAVLINK_MSG_ID_NACK_TM : MAVLink_nack_tm_message,
+        MAVLINK_MSG_ID_WACK_TM : MAVLink_wack_tm_message,
         MAVLINK_MSG_ID_GPS_TM : MAVLink_gps_tm_message,
         MAVLINK_MSG_ID_IMU_TM : MAVLink_imu_tm_message,
         MAVLINK_MSG_ID_PRESSURE_TM : MAVLink_pressure_tm_message,
@@ -2826,14 +2959,11 @@ mavlink_map = {
         MAVLINK_MSG_ID_REGISTRY_FLOAT_TM : MAVLink_registry_float_tm_message,
         MAVLINK_MSG_ID_REGISTRY_INT_TM : MAVLink_registry_int_tm_message,
         MAVLINK_MSG_ID_REGISTRY_COORD_TM : MAVLink_registry_coord_tm_message,
-        MAVLINK_MSG_ID_RECEIVER_TM : MAVLink_receiver_tm_message,
         MAVLINK_MSG_ID_ARP_TM : MAVLink_arp_tm_message,
-        MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC : MAVLink_set_antenna_coordinates_arp_tc_message,
-        MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC : MAVLink_set_rocket_coordinates_arp_tc_message,
         MAVLINK_MSG_ID_SYS_TM : MAVLink_sys_tm_message,
-        MAVLINK_MSG_ID_FSM_TM : MAVLink_fsm_tm_message,
         MAVLINK_MSG_ID_LOGGER_TM : MAVLink_logger_tm_message,
         MAVLINK_MSG_ID_MAVLINK_STATS_TM : MAVLink_mavlink_stats_tm_message,
+        MAVLINK_MSG_ID_CAN_STATS_TM : MAVLink_can_stats_tm_message,
         MAVLINK_MSG_ID_TASK_STATS_TM : MAVLink_task_stats_tm_message,
         MAVLINK_MSG_ID_ADA_TM : MAVLink_ada_tm_message,
         MAVLINK_MSG_ID_NAS_TM : MAVLink_nas_tm_message,
@@ -3377,41 +3507,41 @@ class MAVLink(object):
                 '''
                 return self.send(self.set_servo_angle_tc_encode(servo_id, angle), force_mavlink1=force_mavlink1)
 
-        def wiggle_servo_tc_encode(self, servo_id):
+        def reset_servo_tc_encode(self, servo_id):
                 '''
-                Wiggles the specified servo
+                Resets the specified servo
 
                 servo_id                  : A member of the ServosList enum (type:uint8_t)
 
                 '''
-                return MAVLink_wiggle_servo_tc_message(servo_id)
+                return MAVLink_reset_servo_tc_message(servo_id)
 
-        def wiggle_servo_tc_send(self, servo_id, force_mavlink1=False):
+        def reset_servo_tc_send(self, servo_id, force_mavlink1=False):
                 '''
-                Wiggles the specified servo
+                Resets the specified servo
 
                 servo_id                  : A member of the ServosList enum (type:uint8_t)
 
                 '''
-                return self.send(self.wiggle_servo_tc_encode(servo_id), force_mavlink1=force_mavlink1)
+                return self.send(self.reset_servo_tc_encode(servo_id), force_mavlink1=force_mavlink1)
 
-        def reset_servo_tc_encode(self, servo_id):
+        def wiggle_servo_tc_encode(self, servo_id):
                 '''
-                Resets the specified servo
+                Wiggles the specified servo
 
                 servo_id                  : A member of the ServosList enum (type:uint8_t)
 
                 '''
-                return MAVLink_reset_servo_tc_message(servo_id)
+                return MAVLink_wiggle_servo_tc_message(servo_id)
 
-        def reset_servo_tc_send(self, servo_id, force_mavlink1=False):
+        def wiggle_servo_tc_send(self, servo_id, force_mavlink1=False):
                 '''
-                Resets the specified servo
+                Wiggles the specified servo
 
                 servo_id                  : A member of the ServosList enum (type:uint8_t)
 
                 '''
-                return self.send(self.reset_servo_tc_encode(servo_id), force_mavlink1=force_mavlink1)
+                return self.send(self.wiggle_servo_tc_encode(servo_id), force_mavlink1=force_mavlink1)
 
         def set_reference_altitude_tc_encode(self, ref_altitude):
                 '''
@@ -3471,6 +3601,30 @@ class MAVLink(object):
                 '''
                 return self.send(self.set_orientation_tc_encode(yaw, pitch, roll), force_mavlink1=force_mavlink1)
 
+        def set_orientation_quat_tc_encode(self, quat_x, quat_y, quat_z, quat_w):
+                '''
+                Sets current orientation for the navigation system using a quaternion
+
+                quat_x                    : Quaternion x component (type:float)
+                quat_y                    : Quaternion y component (type:float)
+                quat_z                    : Quaternion z component (type:float)
+                quat_w                    : Quaternion w component (type:float)
+
+                '''
+                return MAVLink_set_orientation_quat_tc_message(quat_x, quat_y, quat_z, quat_w)
+
+        def set_orientation_quat_tc_send(self, quat_x, quat_y, quat_z, quat_w, force_mavlink1=False):
+                '''
+                Sets current orientation for the navigation system using a quaternion
+
+                quat_x                    : Quaternion x component (type:float)
+                quat_y                    : Quaternion y component (type:float)
+                quat_z                    : Quaternion z component (type:float)
+                quat_w                    : Quaternion w component (type:float)
+
+                '''
+                return self.send(self.set_orientation_quat_tc_encode(quat_x, quat_y, quat_z, quat_w), force_mavlink1=force_mavlink1)
+
         def set_coordinates_tc_encode(self, latitude, longitude):
                 '''
                 Sets current coordinates
@@ -3551,7 +3705,7 @@ class MAVLink(object):
 
         def set_algorithm_tc_encode(self, algorithm_number):
                 '''
-                Sets the algorithm number (for parafoil guidance and GSE tars)
+                Sets the algorithm number (for parafoil guidance)
 
                 algorithm_number          : Algorithm number (type:uint8_t)
 
@@ -3560,7 +3714,7 @@ class MAVLink(object):
 
         def set_algorithm_tc_send(self, algorithm_number, force_mavlink1=False):
                 '''
-                Sets the algorithm number (for parafoil guidance and GSE tars)
+                Sets the algorithm number (for parafoil guidance)
 
                 algorithm_number          : Algorithm number (type:uint8_t)
 
@@ -3657,7 +3811,45 @@ class MAVLink(object):
                 timing                    : Timing in [ms] [ms] (type:uint32_t)
 
                 '''
-                return self.send(self.set_ignition_time_tc_encode(timing), force_mavlink1=force_mavlink1)
+                return self.send(self.set_ignition_time_tc_encode(timing), force_mavlink1=force_mavlink1)
+
+        def set_nitrogen_time_tc_encode(self, timing):
+                '''
+                Sets the time in ms that the nitrogen will stay open
+
+                timing                    : Timing in [ms] [ms] (type:uint32_t)
+
+                '''
+                return MAVLink_set_nitrogen_time_tc_message(timing)
+
+        def set_nitrogen_time_tc_send(self, timing, force_mavlink1=False):
+                '''
+                Sets the time in ms that the nitrogen will stay open
+
+                timing                    : Timing in [ms] [ms] (type:uint32_t)
+
+                '''
+                return self.send(self.set_nitrogen_time_tc_encode(timing), force_mavlink1=force_mavlink1)
+
+        def set_cooling_time_tc_encode(self, timing):
+                '''
+                Sets the time in ms that the system will wait before disarming after
+                firing
+
+                timing                    : Timing in [ms] [ms] (type:uint32_t)
+
+                '''
+                return MAVLink_set_cooling_time_tc_message(timing)
+
+        def set_cooling_time_tc_send(self, timing, force_mavlink1=False):
+                '''
+                Sets the time in ms that the system will wait before disarming after
+                firing
+
+                timing                    : Timing in [ms] [ms] (type:uint32_t)
+
+                '''
+                return self.send(self.set_cooling_time_tc_encode(timing), force_mavlink1=force_mavlink1)
 
         def set_stepper_angle_tc_encode(self, stepper_id, angle):
                 '''
@@ -3699,48 +3891,92 @@ class MAVLink(object):
                 '''
                 return self.send(self.set_stepper_steps_tc_encode(stepper_id, steps), force_mavlink1=force_mavlink1)
 
-        def set_nitrogen_time_tc_encode(self, timing):
+        def set_stepper_multiplier_tc_encode(self, stepper_id, multiplier):
                 '''
-                Sets the time in ms that the nitrogen will stay open
+                Set the multiplier of the stepper
 
-                timing                    : Timing in [ms] [ms] (type:uint32_t)
+                stepper_id                : A member of the StepperList enum (type:uint8_t)
+                multiplier                : Multiplier (type:float)
 
                 '''
-                return MAVLink_set_nitrogen_time_tc_message(timing)
+                return MAVLink_set_stepper_multiplier_tc_message(stepper_id, multiplier)
 
-        def set_nitrogen_time_tc_send(self, timing, force_mavlink1=False):
+        def set_stepper_multiplier_tc_send(self, stepper_id, multiplier, force_mavlink1=False):
                 '''
-                Sets the time in ms that the nitrogen will stay open
+                Set the multiplier of the stepper
 
-                timing                    : Timing in [ms] [ms] (type:uint32_t)
+                stepper_id                : A member of the StepperList enum (type:uint8_t)
+                multiplier                : Multiplier (type:float)
 
                 '''
-                return self.send(self.set_nitrogen_time_tc_encode(timing), force_mavlink1=force_mavlink1)
+                return self.send(self.set_stepper_multiplier_tc_encode(stepper_id, multiplier), force_mavlink1=force_mavlink1)
 
-        def set_cooling_time_tc_encode(self, timing):
+        def set_antenna_coordinates_arp_tc_encode(self, latitude, longitude, height):
                 '''
-                Sets the time in ms that the system will wait before disarming after
-                firing
+                Sets current antennas coordinates
 
-                timing                    : Timing in [ms] [ms] (type:uint32_t)
+                latitude                  : Latitude [deg] (type:float)
+                longitude                 : Longitude [deg] (type:float)
+                height                    : Height [m] (type:float)
 
                 '''
-                return MAVLink_set_cooling_time_tc_message(timing)
+                return MAVLink_set_antenna_coordinates_arp_tc_message(latitude, longitude, height)
 
-        def set_cooling_time_tc_send(self, timing, force_mavlink1=False):
+        def set_antenna_coordinates_arp_tc_send(self, latitude, longitude, height, force_mavlink1=False):
                 '''
-                Sets the time in ms that the system will wait before disarming after
-                firing
+                Sets current antennas coordinates
 
-                timing                    : Timing in [ms] [ms] (type:uint32_t)
+                latitude                  : Latitude [deg] (type:float)
+                longitude                 : Longitude [deg] (type:float)
+                height                    : Height [m] (type:float)
 
                 '''
-                return self.send(self.set_cooling_time_tc_encode(timing), force_mavlink1=force_mavlink1)
+                return self.send(self.set_antenna_coordinates_arp_tc_encode(latitude, longitude, height), force_mavlink1=force_mavlink1)
+
+        def set_rocket_coordinates_arp_tc_encode(self, latitude, longitude, height):
+                '''
+                Sets current rocket coordinates
+
+                latitude                  : Latitude [deg] (type:float)
+                longitude                 : Longitude [deg] (type:float)
+                height                    : Height [m] (type:float)
+
+                '''
+                return MAVLink_set_rocket_coordinates_arp_tc_message(latitude, longitude, height)
+
+        def set_rocket_coordinates_arp_tc_send(self, latitude, longitude, height, force_mavlink1=False):
+                '''
+                Sets current rocket coordinates
+
+                latitude                  : Latitude [deg] (type:float)
+                longitude                 : Longitude [deg] (type:float)
+                height                    : Height [m] (type:float)
+
+                '''
+                return self.send(self.set_rocket_coordinates_arp_tc_encode(latitude, longitude, height), force_mavlink1=force_mavlink1)
+
+        def arp_command_tc_encode(self, command_id):
+                '''
+                TC containing a command with no parameters that trigger some action
+
+                command_id                : A member of the MavArpCommandList enum (type:uint8_t)
+
+                '''
+                return MAVLink_arp_command_tc_message(command_id)
+
+        def arp_command_tc_send(self, command_id, force_mavlink1=False):
+                '''
+                TC containing a command with no parameters that trigger some action
+
+                command_id                : A member of the MavArpCommandList enum (type:uint8_t)
+
+                '''
+                return self.send(self.arp_command_tc_encode(command_id), force_mavlink1=force_mavlink1)
 
         def ack_tm_encode(self, recv_msgid, seq_ack):
                 '''
                 TM containing an ACK message to notify that the message has been
-                received
+                processed correctly
 
                 recv_msgid                : Message id of the received message (type:uint8_t)
                 seq_ack                   : Sequence number of the received message (type:uint8_t)
@@ -3751,7 +3987,7 @@ class MAVLink(object):
         def ack_tm_send(self, recv_msgid, seq_ack, force_mavlink1=False):
                 '''
                 TM containing an ACK message to notify that the message has been
-                received
+                processed correctly
 
                 recv_msgid                : Message id of the received message (type:uint8_t)
                 seq_ack                   : Sequence number of the received message (type:uint8_t)
@@ -3759,27 +3995,53 @@ class MAVLink(object):
                 '''
                 return self.send(self.ack_tm_encode(recv_msgid, seq_ack), force_mavlink1=force_mavlink1)
 
-        def nack_tm_encode(self, recv_msgid, seq_ack):
+        def nack_tm_encode(self, recv_msgid, seq_ack, err_id):
                 '''
                 TM containing a NACK message to notify that the received message was
                 invalid
 
                 recv_msgid                : Message id of the received message (type:uint8_t)
                 seq_ack                   : Sequence number of the received message (type:uint8_t)
+                err_id                    : Error core that generated the NACK (type:uint16_t)
 
                 '''
-                return MAVLink_nack_tm_message(recv_msgid, seq_ack)
+                return MAVLink_nack_tm_message(recv_msgid, seq_ack, err_id)
 
-        def nack_tm_send(self, recv_msgid, seq_ack, force_mavlink1=False):
+        def nack_tm_send(self, recv_msgid, seq_ack, err_id, force_mavlink1=False):
                 '''
                 TM containing a NACK message to notify that the received message was
                 invalid
 
                 recv_msgid                : Message id of the received message (type:uint8_t)
                 seq_ack                   : Sequence number of the received message (type:uint8_t)
+                err_id                    : Error core that generated the NACK (type:uint16_t)
+
+                '''
+                return self.send(self.nack_tm_encode(recv_msgid, seq_ack, err_id), force_mavlink1=force_mavlink1)
+
+        def wack_tm_encode(self, recv_msgid, seq_ack, err_id):
+                '''
+                TM containing an ACK message to notify that the message has been
+                processed with a warning
+
+                recv_msgid                : Message id of the received message (type:uint8_t)
+                seq_ack                   : Sequence number of the received message (type:uint8_t)
+                err_id                    : Error core that generated the WACK (type:uint16_t)
 
                 '''
-                return self.send(self.nack_tm_encode(recv_msgid, seq_ack), force_mavlink1=force_mavlink1)
+                return MAVLink_wack_tm_message(recv_msgid, seq_ack, err_id)
+
+        def wack_tm_send(self, recv_msgid, seq_ack, err_id, force_mavlink1=False):
+                '''
+                TM containing an ACK message to notify that the message has been
+                processed with a warning
+
+                recv_msgid                : Message id of the received message (type:uint8_t)
+                seq_ack                   : Sequence number of the received message (type:uint8_t)
+                err_id                    : Error core that generated the WACK (type:uint16_t)
+
+                '''
+                return self.send(self.wack_tm_encode(recv_msgid, seq_ack, err_id), force_mavlink1=force_mavlink1)
 
         def gps_tm_encode(self, timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites):
                 '''
@@ -4039,25 +4301,27 @@ class MAVLink(object):
                 '''
                 return self.send(self.attitude_tm_encode(timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w), force_mavlink1=force_mavlink1)
 
-        def sensor_state_tm_encode(self, sensor_name, state):
+        def sensor_state_tm_encode(self, sensor_name, initialized, enabled):
                 '''
                 
 
                 sensor_name               : Sensor name (type:char)
-                state                     : Boolean that represents the init state (type:uint8_t)
+                initialized               : Boolean that represents the init state (type:uint8_t)
+                enabled                   : Boolean that represents the enabled state (type:uint8_t)
 
                 '''
-                return MAVLink_sensor_state_tm_message(sensor_name, state)
+                return MAVLink_sensor_state_tm_message(sensor_name, initialized, enabled)
 
-        def sensor_state_tm_send(self, sensor_name, state, force_mavlink1=False):
+        def sensor_state_tm_send(self, sensor_name, initialized, enabled, force_mavlink1=False):
                 '''
                 
 
                 sensor_name               : Sensor name (type:char)
-                state                     : Boolean that represents the init state (type:uint8_t)
+                initialized               : Boolean that represents the init state (type:uint8_t)
+                enabled                   : Boolean that represents the enabled state (type:uint8_t)
 
                 '''
-                return self.send(self.sensor_state_tm_encode(sensor_name, state), force_mavlink1=force_mavlink1)
+                return self.send(self.sensor_state_tm_encode(sensor_name, initialized, enabled), force_mavlink1=force_mavlink1)
 
         def servo_tm_encode(self, servo_id, servo_position):
                 '''
@@ -4179,63 +4443,7 @@ class MAVLink(object):
                 '''
                 return self.send(self.registry_coord_tm_encode(timestamp, key_id, key_name, latitude, longitude), force_mavlink1=force_mavlink1)
 
-        def receiver_tm_encode(self, timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage):
-                '''
-                
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                main_radio_present        : Boolean indicating the presence of the main radio (type:uint8_t)
-                main_packet_tx_error_count        : Number of errors during send (type:uint16_t)
-                main_tx_bitrate           : Send bitrate [b/s] (type:uint16_t)
-                main_packet_rx_success_count        : Number of succesfull received mavlink packets (type:uint16_t)
-                main_packet_rx_drop_count        : Number of dropped mavlink packets (type:uint16_t)
-                main_rx_bitrate           : Receive bitrate [b/s] (type:uint16_t)
-                main_rx_rssi              : Receive RSSI [dBm] (type:float)
-                main_rx_fei               : Receive frequency error index [Hz] (type:float)
-                payload_radio_present        : Boolean indicating the presence of the payload radio (type:uint8_t)
-                payload_packet_tx_error_count        : Number of errors during send (type:uint16_t)
-                payload_tx_bitrate        : Send bitrate [b/s] (type:uint16_t)
-                payload_packet_rx_success_count        : Number of succesfull received mavlink packets (type:uint16_t)
-                payload_packet_rx_drop_count        : Number of dropped mavlink packets (type:uint16_t)
-                payload_rx_bitrate        : Receive bitrate [b/s] (type:uint16_t)
-                payload_rx_rssi           : Receive RSSI [dBm] (type:float)
-                payload_rx_fei            : Receive frequency error index [Hz] (type:float)
-                ethernet_present          : Boolean indicating the presence of the ethernet module (type:uint8_t)
-                ethernet_status           : Status flag indicating the status of the ethernet PHY (type:uint8_t)
-                battery_voltage           : Battery voltage [V] (type:float)
-
-                '''
-                return MAVLink_receiver_tm_message(timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage)
-
-        def receiver_tm_send(self, timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage, force_mavlink1=False):
-                '''
-                
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                main_radio_present        : Boolean indicating the presence of the main radio (type:uint8_t)
-                main_packet_tx_error_count        : Number of errors during send (type:uint16_t)
-                main_tx_bitrate           : Send bitrate [b/s] (type:uint16_t)
-                main_packet_rx_success_count        : Number of succesfull received mavlink packets (type:uint16_t)
-                main_packet_rx_drop_count        : Number of dropped mavlink packets (type:uint16_t)
-                main_rx_bitrate           : Receive bitrate [b/s] (type:uint16_t)
-                main_rx_rssi              : Receive RSSI [dBm] (type:float)
-                main_rx_fei               : Receive frequency error index [Hz] (type:float)
-                payload_radio_present        : Boolean indicating the presence of the payload radio (type:uint8_t)
-                payload_packet_tx_error_count        : Number of errors during send (type:uint16_t)
-                payload_tx_bitrate        : Send bitrate [b/s] (type:uint16_t)
-                payload_packet_rx_success_count        : Number of succesfull received mavlink packets (type:uint16_t)
-                payload_packet_rx_drop_count        : Number of dropped mavlink packets (type:uint16_t)
-                payload_rx_bitrate        : Receive bitrate [b/s] (type:uint16_t)
-                payload_rx_rssi           : Receive RSSI [dBm] (type:float)
-                payload_rx_fei            : Receive frequency error index [Hz] (type:float)
-                ethernet_present          : Boolean indicating the presence of the ethernet module (type:uint8_t)
-                ethernet_status           : Status flag indicating the status of the ethernet PHY (type:uint8_t)
-                battery_voltage           : Battery voltage [V] (type:float)
-
-                '''
-                return self.send(self.receiver_tm_encode(timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage), force_mavlink1=force_mavlink1)
-
-        def arp_tm_encode(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage):
+        def arp_tm_encode(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, ethernet_present, ethernet_status, battery_voltage):
                 '''
                 
 
@@ -4262,14 +4470,21 @@ class MAVLink(object):
                 main_packet_rx_drop_count        : Number of dropped mavlink packets (type:uint16_t)
                 main_rx_bitrate           : Receive bitrate [b/s] (type:uint16_t)
                 main_rx_rssi              : Receive RSSI [dBm] (type:float)
+                payload_radio_present        : Boolean indicating the presence of the payload radio (type:uint8_t)
+                payload_packet_tx_error_count        : Number of errors during send (type:uint16_t)
+                payload_tx_bitrate        : Send bitrate [b/s] (type:uint16_t)
+                payload_packet_rx_success_count        : Number of succesfull received mavlink packets (type:uint16_t)
+                payload_packet_rx_drop_count        : Number of dropped mavlink packets (type:uint16_t)
+                payload_rx_bitrate        : Receive bitrate [b/s] (type:uint16_t)
+                payload_rx_rssi           : Receive RSSI [dBm] (type:float)
                 ethernet_present          : Boolean indicating the presence of the ethernet module (type:uint8_t)
                 ethernet_status           : Status flag indicating the status of the ethernet PHY (type:uint8_t)
                 battery_voltage           : Battery voltage [V] (type:float)
 
                 '''
-                return MAVLink_arp_tm_message(timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage)
+                return MAVLink_arp_tm_message(timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, ethernet_present, ethernet_status, battery_voltage)
 
-        def arp_tm_send(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage, force_mavlink1=False):
+        def arp_tm_send(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, ethernet_present, ethernet_status, battery_voltage, force_mavlink1=False):
                 '''
                 
 
@@ -4296,54 +4511,21 @@ class MAVLink(object):
                 main_packet_rx_drop_count        : Number of dropped mavlink packets (type:uint16_t)
                 main_rx_bitrate           : Receive bitrate [b/s] (type:uint16_t)
                 main_rx_rssi              : Receive RSSI [dBm] (type:float)
+                payload_radio_present        : Boolean indicating the presence of the payload radio (type:uint8_t)
+                payload_packet_tx_error_count        : Number of errors during send (type:uint16_t)
+                payload_tx_bitrate        : Send bitrate [b/s] (type:uint16_t)
+                payload_packet_rx_success_count        : Number of succesfull received mavlink packets (type:uint16_t)
+                payload_packet_rx_drop_count        : Number of dropped mavlink packets (type:uint16_t)
+                payload_rx_bitrate        : Receive bitrate [b/s] (type:uint16_t)
+                payload_rx_rssi           : Receive RSSI [dBm] (type:float)
                 ethernet_present          : Boolean indicating the presence of the ethernet module (type:uint8_t)
                 ethernet_status           : Status flag indicating the status of the ethernet PHY (type:uint8_t)
                 battery_voltage           : Battery voltage [V] (type:float)
 
                 '''
-                return self.send(self.arp_tm_encode(timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage), force_mavlink1=force_mavlink1)
-
-        def set_antenna_coordinates_arp_tc_encode(self, latitude, longitude):
-                '''
-                Sets current antennas coordinates
-
-                latitude                  : Latitude [deg] (type:float)
-                longitude                 : Longitude [deg] (type:float)
-
-                '''
-                return MAVLink_set_antenna_coordinates_arp_tc_message(latitude, longitude)
-
-        def set_antenna_coordinates_arp_tc_send(self, latitude, longitude, force_mavlink1=False):
-                '''
-                Sets current antennas coordinates
-
-                latitude                  : Latitude [deg] (type:float)
-                longitude                 : Longitude [deg] (type:float)
-
-                '''
-                return self.send(self.set_antenna_coordinates_arp_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1)
-
-        def set_rocket_coordinates_arp_tc_encode(self, latitude, longitude):
-                '''
-                Sets current rocket coordinates
-
-                latitude                  : Latitude [deg] (type:float)
-                longitude                 : Longitude [deg] (type:float)
-
-                '''
-                return MAVLink_set_rocket_coordinates_arp_tc_message(latitude, longitude)
-
-        def set_rocket_coordinates_arp_tc_send(self, latitude, longitude, force_mavlink1=False):
-                '''
-                Sets current rocket coordinates
-
-                latitude                  : Latitude [deg] (type:float)
-                longitude                 : Longitude [deg] (type:float)
+                return self.send(self.arp_tm_encode(timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, ethernet_present, ethernet_status, battery_voltage), force_mavlink1=force_mavlink1)
 
-                '''
-                return self.send(self.set_rocket_coordinates_arp_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1)
-
-        def sys_tm_encode(self, timestamp, logger, event_broker, radio, pin_observer, sensors, board_scheduler):
+        def sys_tm_encode(self, timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler):
                 '''
                 System status telemetry
 
@@ -4351,14 +4533,16 @@ class MAVLink(object):
                 logger                    : True if the logger started correctly (type:uint8_t)
                 event_broker              : True if the event broker started correctly (type:uint8_t)
                 radio                     : True if the radio started correctly (type:uint8_t)
-                pin_observer              : True if the pin observer started correctly (type:uint8_t)
                 sensors                   : True if the sensors started correctly (type:uint8_t)
-                board_scheduler           : True if the board scheduler is running (type:uint8_t)
+                actuators                 : True if the sensors started correctly (type:uint8_t)
+                pin_handler               : True if the pin observer started correctly (type:uint8_t)
+                can_handler               : True if the can handler started correctly (type:uint8_t)
+                scheduler                 : True if the board scheduler is running (type:uint8_t)
 
                 '''
-                return MAVLink_sys_tm_message(timestamp, logger, event_broker, radio, pin_observer, sensors, board_scheduler)
+                return MAVLink_sys_tm_message(timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler)
 
-        def sys_tm_send(self, timestamp, logger, event_broker, radio, pin_observer, sensors, board_scheduler, force_mavlink1=False):
+        def sys_tm_send(self, timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler, force_mavlink1=False):
                 '''
                 System status telemetry
 
@@ -4366,42 +4550,14 @@ class MAVLink(object):
                 logger                    : True if the logger started correctly (type:uint8_t)
                 event_broker              : True if the event broker started correctly (type:uint8_t)
                 radio                     : True if the radio started correctly (type:uint8_t)
-                pin_observer              : True if the pin observer started correctly (type:uint8_t)
                 sensors                   : True if the sensors started correctly (type:uint8_t)
-                board_scheduler           : True if the board scheduler is running (type:uint8_t)
-
-                '''
-                return self.send(self.sys_tm_encode(timestamp, logger, event_broker, radio, pin_observer, sensors, board_scheduler), force_mavlink1=force_mavlink1)
-
-        def fsm_tm_encode(self, timestamp, ada_state, abk_state, dpl_state, fmm_state, nas_state, wes_state):
-                '''
-                Flight State Machine status telemetry
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                ada_state                 : Apogee Detection Algorithm state (type:uint8_t)
-                abk_state                 : Air Brakes state (type:uint8_t)
-                dpl_state                 : Deployment state (type:uint8_t)
-                fmm_state                 : Flight Mode Manager state (type:uint8_t)
-                nas_state                 : Navigation and Attitude System state (type:uint8_t)
-                wes_state                 : Wind Estimation System state (type:uint8_t)
-
-                '''
-                return MAVLink_fsm_tm_message(timestamp, ada_state, abk_state, dpl_state, fmm_state, nas_state, wes_state)
-
-        def fsm_tm_send(self, timestamp, ada_state, abk_state, dpl_state, fmm_state, nas_state, wes_state, force_mavlink1=False):
-                '''
-                Flight State Machine status telemetry
-
-                timestamp                 : Timestamp [us] (type:uint64_t)
-                ada_state                 : Apogee Detection Algorithm state (type:uint8_t)
-                abk_state                 : Air Brakes state (type:uint8_t)
-                dpl_state                 : Deployment state (type:uint8_t)
-                fmm_state                 : Flight Mode Manager state (type:uint8_t)
-                nas_state                 : Navigation and Attitude System state (type:uint8_t)
-                wes_state                 : Wind Estimation System state (type:uint8_t)
+                actuators                 : True if the sensors started correctly (type:uint8_t)
+                pin_handler               : True if the pin observer started correctly (type:uint8_t)
+                can_handler               : True if the can handler started correctly (type:uint8_t)
+                scheduler                 : True if the board scheduler is running (type:uint8_t)
 
                 '''
-                return self.send(self.fsm_tm_encode(timestamp, ada_state, abk_state, dpl_state, fmm_state, nas_state, wes_state), force_mavlink1=force_mavlink1)
+                return self.send(self.sys_tm_encode(timestamp, logger, event_broker, radio, sensors, actuators, pin_handler, can_handler, scheduler), force_mavlink1=force_mavlink1)
 
         def logger_tm_encode(self, timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time):
                 '''
@@ -4443,7 +4599,7 @@ class MAVLink(object):
 
         def mavlink_stats_tm_encode(self, timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count):
                 '''
-                Status of the TMTCManager telemetry
+                Status of MavlinkDriver
 
                 timestamp                 : When was this logged [us] (type:uint64_t)
                 n_send_queue              : Current len of the occupied portion of the queue (type:uint16_t)
@@ -4464,7 +4620,7 @@ class MAVLink(object):
 
         def mavlink_stats_tm_send(self, timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count, force_mavlink1=False):
                 '''
-                Status of the TMTCManager telemetry
+                Status of MavlinkDriver
 
                 timestamp                 : When was this logged [us] (type:uint64_t)
                 n_send_queue              : Current len of the occupied portion of the queue (type:uint16_t)
@@ -4483,35 +4639,67 @@ class MAVLink(object):
                 '''
                 return self.send(self.mavlink_stats_tm_encode(timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count), force_mavlink1=force_mavlink1)
 
-        def task_stats_tm_encode(self, timestamp, task_id, task_period, task_min, task_max, task_mean, task_stddev):
+        def can_stats_tm_encode(self, timestamp, payload_bit_rate, total_bit_rate, load_percent):
+                '''
+                Status of CanHandler
+
+                timestamp                 : When was this logged [us] (type:uint64_t)
+                payload_bit_rate          : Payload only bitrate (type:float)
+                total_bit_rate            : Total bitrate (type:float)
+                load_percent              : Load percent of the BUS (type:float)
+
+                '''
+                return MAVLink_can_stats_tm_message(timestamp, payload_bit_rate, total_bit_rate, load_percent)
+
+        def can_stats_tm_send(self, timestamp, payload_bit_rate, total_bit_rate, load_percent, force_mavlink1=False):
+                '''
+                Status of CanHandler
+
+                timestamp                 : When was this logged [us] (type:uint64_t)
+                payload_bit_rate          : Payload only bitrate (type:float)
+                total_bit_rate            : Total bitrate (type:float)
+                load_percent              : Load percent of the BUS (type:float)
+
+                '''
+                return self.send(self.can_stats_tm_encode(timestamp, payload_bit_rate, total_bit_rate, load_percent), force_mavlink1=force_mavlink1)
+
+        def task_stats_tm_encode(self, timestamp, task_id, task_period, task_missed_events, task_failed_events, task_activation_mean, task_activation_stddev, task_period_mean, task_period_stddev, task_workload_mean, task_workload_stddev):
                 '''
                 Statistics of the Task Scheduler
 
                 timestamp                 : When was this logged [us] (type:uint64_t)
-                task_id                   : Task ID (type:uint8_t)
-                task_period               : Period of the task [ms] (type:uint16_t)
-                task_min                  : Task min period (type:float)
-                task_max                  : Task max period (type:float)
-                task_mean                 : Task mean period (type:float)
-                task_stddev               : Task period std deviation (type:float)
+                task_id                   : Task ID (type:uint16_t)
+                task_period               : Period of the task [ns] (type:uint16_t)
+                task_missed_events        : Number of missed events (type:uint32_t)
+                task_failed_events        : Number of missed events (type:uint32_t)
+                task_activation_mean        : Task activation mean period (type:float)
+                task_activation_stddev        : Task activation mean standard deviation (type:float)
+                task_period_mean          : Task period mean period (type:float)
+                task_period_stddev        : Task period mean standard deviation (type:float)
+                task_workload_mean        : Task workload mean period (type:float)
+                task_workload_stddev        : Task workload mean standard deviation (type:float)
 
                 '''
-                return MAVLink_task_stats_tm_message(timestamp, task_id, task_period, task_min, task_max, task_mean, task_stddev)
+                return MAVLink_task_stats_tm_message(timestamp, task_id, task_period, task_missed_events, task_failed_events, task_activation_mean, task_activation_stddev, task_period_mean, task_period_stddev, task_workload_mean, task_workload_stddev)
 
-        def task_stats_tm_send(self, timestamp, task_id, task_period, task_min, task_max, task_mean, task_stddev, force_mavlink1=False):
+        def task_stats_tm_send(self, timestamp, task_id, task_period, task_missed_events, task_failed_events, task_activation_mean, task_activation_stddev, task_period_mean, task_period_stddev, task_workload_mean, task_workload_stddev, force_mavlink1=False):
                 '''
                 Statistics of the Task Scheduler
 
                 timestamp                 : When was this logged [us] (type:uint64_t)
-                task_id                   : Task ID (type:uint8_t)
-                task_period               : Period of the task [ms] (type:uint16_t)
-                task_min                  : Task min period (type:float)
-                task_max                  : Task max period (type:float)
-                task_mean                 : Task mean period (type:float)
-                task_stddev               : Task period std deviation (type:float)
+                task_id                   : Task ID (type:uint16_t)
+                task_period               : Period of the task [ns] (type:uint16_t)
+                task_missed_events        : Number of missed events (type:uint32_t)
+                task_failed_events        : Number of missed events (type:uint32_t)
+                task_activation_mean        : Task activation mean period (type:float)
+                task_activation_stddev        : Task activation mean standard deviation (type:float)
+                task_period_mean          : Task period mean period (type:float)
+                task_period_stddev        : Task period mean standard deviation (type:float)
+                task_workload_mean        : Task workload mean period (type:float)
+                task_workload_stddev        : Task workload mean standard deviation (type:float)
 
                 '''
-                return self.send(self.task_stats_tm_encode(timestamp, task_id, task_period, task_min, task_max, task_mean, task_stddev), force_mavlink1=force_mavlink1)
+                return self.send(self.task_stats_tm_encode(timestamp, task_id, task_period, task_missed_events, task_failed_events, task_activation_mean, task_activation_stddev, task_period_mean, task_period_stddev, task_workload_mean, task_workload_stddev), force_mavlink1=force_mavlink1)
 
         def ada_tm_encode(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude):
                 '''
@@ -4619,7 +4807,7 @@ class MAVLink(object):
                 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)
+                corrected_pressure        : Corrected pressure [Pa] (type:float)
 
                 '''
                 return MAVLink_mea_tm_message(timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure)
@@ -4634,12 +4822,12 @@ class MAVLink(object):
                 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)
+                corrected_pressure        : Corrected pressure [Pa] (type:float)
 
                 '''
                 return self.send(self.mea_tm_encode(timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure), force_mavlink1=force_mavlink1)
 
-        def rocket_flight_tm_encode(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error):
+        def rocket_flight_tm_encode(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, temperature):
                 '''
                 High Rate Telemetry
 
@@ -4648,7 +4836,7 @@ class MAVLink(object):
                 fmm_state                 : Flight Mode Manager State (type:uint8_t)
                 dpl_state                 : Deployment Controller State (type:uint8_t)
                 abk_state                 : Airbrake FSM state (type:uint8_t)
-                nas_state                 : Navigation System FSM State (type:uint8_t)
+                nas_state                 : NAS FSM State (type:uint8_t)
                 mea_state                 : MEA Controller State (type:uint8_t)
                 pressure_ada              : Atmospheric pressure estimated by ADA [Pa] (type:float)
                 pressure_digi             : Pressure from digital sensor [Pa] (type:float)
@@ -4672,34 +4860,31 @@ class MAVLink(object):
                 gps_lon                   : Longitude [deg] (type:float)
                 gps_alt                   : GPS Altitude [m] (type:float)
                 abk_angle                 : Air Brakes angle [deg] (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)
-                nas_vn                    : Navigation system estimated north velocity [m/s] (type:float)
-                nas_ve                    : Navigation system estimated east velocity [m/s] (type:float)
-                nas_vd                    : Navigation system estimated down velocity [m/s] (type:float)
-                nas_qx                    : Navigation system estimated attitude (qx) [deg] (type:float)
-                nas_qy                    : Navigation system estimated attitude (qy) [deg] (type:float)
-                nas_qz                    : Navigation system estimated attitude (qz) [deg] (type:float)
-                nas_qw                    : Navigation system estimated attitude (qw) [deg] (type:float)
-                nas_bias_x                : Navigation system gyroscope bias on x axis (type:float)
-                nas_bias_y                : Navigation system gyroscope bias on y axis (type:float)
-                nas_bias_z                : Navigation system gyroscope bias on z axis (type:float)
-                pin_quick_connector        : Quick connector detach pin (type:float)
+                nas_n                     : NAS estimated noth position [deg] (type:float)
+                nas_e                     : NAS estimated east position [deg] (type:float)
+                nas_d                     : NAS estimated down position [m] (type:float)
+                nas_vn                    : NAS estimated north velocity [m/s] (type:float)
+                nas_ve                    : NAS estimated east velocity [m/s] (type:float)
+                nas_vd                    : NAS estimated down velocity [m/s] (type:float)
+                nas_qx                    : NAS estimated attitude (qx) [deg] (type:float)
+                nas_qy                    : NAS estimated attitude (qy) [deg] (type:float)
+                nas_qz                    : NAS estimated attitude (qz) [deg] (type:float)
+                nas_qw                    : NAS estimated attitude (qw) [deg] (type:float)
+                nas_bias_x                : NAS gyroscope bias on x axis (type:float)
+                nas_bias_y                : NAS gyroscope bias on y axis (type:float)
+                nas_bias_z                : NAS gyroscope bias on z axis (type:float)
                 pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 pin_expulsion             : Servo sensor status (1 = actuated, 0 = idle) (type:uint8_t)
                 cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
                 battery_voltage           : Battery voltage [V] (type:float)
                 cam_battery_voltage        : Camera battery voltage [V] (type:float)
-                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, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error)
+                return MAVLink_rocket_flight_tm_message(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, temperature)
 
-        def rocket_flight_tm_send(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error, force_mavlink1=False):
+        def rocket_flight_tm_send(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, temperature, force_mavlink1=False):
                 '''
                 High Rate Telemetry
 
@@ -4708,7 +4893,7 @@ class MAVLink(object):
                 fmm_state                 : Flight Mode Manager State (type:uint8_t)
                 dpl_state                 : Deployment Controller State (type:uint8_t)
                 abk_state                 : Airbrake FSM state (type:uint8_t)
-                nas_state                 : Navigation System FSM State (type:uint8_t)
+                nas_state                 : NAS FSM State (type:uint8_t)
                 mea_state                 : MEA Controller State (type:uint8_t)
                 pressure_ada              : Atmospheric pressure estimated by ADA [Pa] (type:float)
                 pressure_digi             : Pressure from digital sensor [Pa] (type:float)
@@ -4732,40 +4917,37 @@ class MAVLink(object):
                 gps_lon                   : Longitude [deg] (type:float)
                 gps_alt                   : GPS Altitude [m] (type:float)
                 abk_angle                 : Air Brakes angle [deg] (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)
-                nas_vn                    : Navigation system estimated north velocity [m/s] (type:float)
-                nas_ve                    : Navigation system estimated east velocity [m/s] (type:float)
-                nas_vd                    : Navigation system estimated down velocity [m/s] (type:float)
-                nas_qx                    : Navigation system estimated attitude (qx) [deg] (type:float)
-                nas_qy                    : Navigation system estimated attitude (qy) [deg] (type:float)
-                nas_qz                    : Navigation system estimated attitude (qz) [deg] (type:float)
-                nas_qw                    : Navigation system estimated attitude (qw) [deg] (type:float)
-                nas_bias_x                : Navigation system gyroscope bias on x axis (type:float)
-                nas_bias_y                : Navigation system gyroscope bias on y axis (type:float)
-                nas_bias_z                : Navigation system gyroscope bias on z axis (type:float)
-                pin_quick_connector        : Quick connector detach pin (type:float)
+                nas_n                     : NAS estimated noth position [deg] (type:float)
+                nas_e                     : NAS estimated east position [deg] (type:float)
+                nas_d                     : NAS estimated down position [m] (type:float)
+                nas_vn                    : NAS estimated north velocity [m/s] (type:float)
+                nas_ve                    : NAS estimated east velocity [m/s] (type:float)
+                nas_vd                    : NAS estimated down velocity [m/s] (type:float)
+                nas_qx                    : NAS estimated attitude (qx) [deg] (type:float)
+                nas_qy                    : NAS estimated attitude (qy) [deg] (type:float)
+                nas_qz                    : NAS estimated attitude (qz) [deg] (type:float)
+                nas_qw                    : NAS estimated attitude (qw) [deg] (type:float)
+                nas_bias_x                : NAS gyroscope bias on x axis (type:float)
+                nas_bias_y                : NAS gyroscope bias on y axis (type:float)
+                nas_bias_z                : NAS gyroscope bias on z axis (type:float)
                 pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 pin_expulsion             : Servo sensor status (1 = actuated, 0 = idle) (type:uint8_t)
                 cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
                 battery_voltage           : Battery voltage [V] (type:float)
                 cam_battery_voltage        : Camera battery voltage [V] (type:float)
-                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, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error), force_mavlink1=force_mavlink1)
+                return self.send(self.rocket_flight_tm_encode(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, temperature), force_mavlink1=force_mavlink1)
 
-        def payload_flight_tm_encode(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, 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_launch, pin_nosecone, cutter_presence, battery_voltage, cam_battery_voltage, temperature):
                 '''
                 High Rate Telemetry
 
                 timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
                 fmm_state                 : Flight Mode Manager State (type:uint8_t)
-                nas_state                 : Navigation System FSM State (type:uint8_t)
+                nas_state                 : NAS FSM State (type:uint8_t)
                 wes_state                 : Wind Estimation System FSM State (type:uint8_t)
                 pressure_digi             : Pressure from digital sensor [Pa] (type:float)
                 pressure_static           : Pressure from static port [Pa] (type:float)
@@ -4786,39 +4968,38 @@ class MAVLink(object):
                 gps_alt                   : GPS Altitude [m] (type:float)
                 left_servo_angle          : Left servo motor angle [deg] (type:float)
                 right_servo_angle         : Right servo motor angle [deg] (type:float)
-                nas_n                     : Navigation system estimated noth position [deg] (type:float)
-                nas_e                     : Navigation system estimated east position [deg] (type:float)
-                nas_d                     : Navigation system estimated down position [m] (type:float)
-                nas_vn                    : Navigation system estimated north velocity [m/s] (type:float)
-                nas_ve                    : Navigation system estimated east velocity [m/s] (type:float)
-                nas_vd                    : Navigation system estimated down velocity [m/s] (type:float)
-                nas_qx                    : Navigation system estimated attitude (qx) [deg] (type:float)
-                nas_qy                    : Navigation system estimated attitude (qy) [deg] (type:float)
-                nas_qz                    : Navigation system estimated attitude (qz) [deg] (type:float)
-                nas_qw                    : Navigation system estimated attitude (qw) [deg] (type:float)
-                nas_bias_x                : Navigation system gyroscope bias on x axis (type:float)
-                nas_bias_y                : Navigation system gyroscope bias on y axis (type:float)
-                nas_bias_z                : Navigation system gyroscope bias on z axis (type:float)
+                nas_n                     : NAS estimated noth position [deg] (type:float)
+                nas_e                     : NAS estimated east position [deg] (type:float)
+                nas_d                     : NAS estimated down position [m] (type:float)
+                nas_vn                    : NAS estimated north velocity [m/s] (type:float)
+                nas_ve                    : NAS estimated east velocity [m/s] (type:float)
+                nas_vd                    : NAS estimated down velocity [m/s] (type:float)
+                nas_qx                    : NAS estimated attitude (qx) [deg] (type:float)
+                nas_qy                    : NAS estimated attitude (qy) [deg] (type:float)
+                nas_qz                    : NAS estimated attitude (qz) [deg] (type:float)
+                nas_qw                    : NAS estimated attitude (qw) [deg] (type:float)
+                nas_bias_x                : NAS gyroscope bias on x axis (type:float)
+                nas_bias_y                : NAS gyroscope bias on y axis (type:float)
+                nas_bias_z                : NAS gyroscope bias on z axis (type:float)
                 wes_n                     : Wind estimated north velocity [m/s] (type:float)
                 wes_e                     : Wind estimated east velocity [m/s] (type:float)
+                pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
+                cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
                 battery_voltage           : Battery voltage [V] (type:float)
                 cam_battery_voltage        : Camera battery voltage [V] (type:float)
-                current_consumption        : Battery current [A] (type:float)
-                cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
                 temperature               : Temperature [degC] (type:float)
-                logger_error              : Logger error (0 = no error) (type:int8_t)
 
                 '''
-                return MAVLink_payload_flight_tm_message(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, 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_launch, pin_nosecone, cutter_presence, battery_voltage, cam_battery_voltage, temperature)
 
-        def payload_flight_tm_send(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, temperature, logger_error, force_mavlink1=False):
+        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_launch, pin_nosecone, cutter_presence, battery_voltage, cam_battery_voltage, temperature, force_mavlink1=False):
                 '''
                 High Rate Telemetry
 
                 timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
                 fmm_state                 : Flight Mode Manager State (type:uint8_t)
-                nas_state                 : Navigation System FSM State (type:uint8_t)
+                nas_state                 : NAS FSM State (type:uint8_t)
                 wes_state                 : Wind Estimation System FSM State (type:uint8_t)
                 pressure_digi             : Pressure from digital sensor [Pa] (type:float)
                 pressure_static           : Pressure from static port [Pa] (type:float)
@@ -4839,33 +5020,32 @@ class MAVLink(object):
                 gps_alt                   : GPS Altitude [m] (type:float)
                 left_servo_angle          : Left servo motor angle [deg] (type:float)
                 right_servo_angle         : Right servo motor angle [deg] (type:float)
-                nas_n                     : Navigation system estimated noth position [deg] (type:float)
-                nas_e                     : Navigation system estimated east position [deg] (type:float)
-                nas_d                     : Navigation system estimated down position [m] (type:float)
-                nas_vn                    : Navigation system estimated north velocity [m/s] (type:float)
-                nas_ve                    : Navigation system estimated east velocity [m/s] (type:float)
-                nas_vd                    : Navigation system estimated down velocity [m/s] (type:float)
-                nas_qx                    : Navigation system estimated attitude (qx) [deg] (type:float)
-                nas_qy                    : Navigation system estimated attitude (qy) [deg] (type:float)
-                nas_qz                    : Navigation system estimated attitude (qz) [deg] (type:float)
-                nas_qw                    : Navigation system estimated attitude (qw) [deg] (type:float)
-                nas_bias_x                : Navigation system gyroscope bias on x axis (type:float)
-                nas_bias_y                : Navigation system gyroscope bias on y axis (type:float)
-                nas_bias_z                : Navigation system gyroscope bias on z axis (type:float)
+                nas_n                     : NAS estimated noth position [deg] (type:float)
+                nas_e                     : NAS estimated east position [deg] (type:float)
+                nas_d                     : NAS estimated down position [m] (type:float)
+                nas_vn                    : NAS estimated north velocity [m/s] (type:float)
+                nas_ve                    : NAS estimated east velocity [m/s] (type:float)
+                nas_vd                    : NAS estimated down velocity [m/s] (type:float)
+                nas_qx                    : NAS estimated attitude (qx) [deg] (type:float)
+                nas_qy                    : NAS estimated attitude (qy) [deg] (type:float)
+                nas_qz                    : NAS estimated attitude (qz) [deg] (type:float)
+                nas_qw                    : NAS estimated attitude (qw) [deg] (type:float)
+                nas_bias_x                : NAS gyroscope bias on x axis (type:float)
+                nas_bias_y                : NAS gyroscope bias on y axis (type:float)
+                nas_bias_z                : NAS gyroscope bias on z axis (type:float)
                 wes_n                     : Wind estimated north velocity [m/s] (type:float)
                 wes_e                     : Wind estimated east velocity [m/s] (type:float)
+                pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
+                cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
                 battery_voltage           : Battery voltage [V] (type:float)
                 cam_battery_voltage        : Camera battery voltage [V] (type:float)
-                current_consumption        : Battery current [A] (type:float)
-                cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
                 temperature               : Temperature [degC] (type:float)
-                logger_error              : Logger error (0 = no error) (type:int8_t)
 
                 '''
-                return self.send(self.payload_flight_tm_encode(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, 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_launch, pin_nosecone, cutter_presence, battery_voltage, cam_battery_voltage, temperature), 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):
+        def rocket_stats_tm_encode(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_bay_max_pressure, cpu_load, free_heap, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, hil_state):
                 '''
                 Low Rate Telemetry
 
@@ -4884,14 +5064,22 @@ class MAVLink(object):
                 apogee_alt                : Apogee altitude [m] (type:float)
                 min_pressure              : Apogee pressure - Digital barometer [Pa] (type:float)
                 ada_min_pressure          : Apogee pressure - ADA filtered [Pa] (type:float)
-                dpl_vane_max_pressure        : Max pressure in the deployment bay during drogue deployment [Pa] (type:float)
+                dpl_bay_max_pressure        : Max pressure in the deployment bay during drogue deployment [Pa] (type:float)
                 cpu_load                  : CPU load in percentage (type:float)
                 free_heap                 : Amount of available heap in memory (type:uint32_t)
+                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+                log_good                  : 0 if log failed, 1 otherwise (type:int32_t)
+                payload_board_state        : Main board fmm state (type:uint8_t)
+                motor_board_state         : Motor board fmm state (type:uint8_t)
+                payload_can_status        : Main CAN status (type:uint8_t)
+                motor_can_status          : Motor CAN status (type:uint8_t)
+                rig_can_status            : RIG CAN status (type:uint8_t)
+                hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
 
                 '''
-                return MAVLink_rocket_stats_tm_message(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)
+                return MAVLink_rocket_stats_tm_message(liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_bay_max_pressure, cpu_load, free_heap, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, hil_state)
 
-        def rocket_stats_tm_send(self, 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, force_mavlink1=False):
+        def rocket_stats_tm_send(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_bay_max_pressure, cpu_load, free_heap, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, hil_state, force_mavlink1=False):
                 '''
                 Low Rate Telemetry
 
@@ -4910,14 +5098,22 @@ class MAVLink(object):
                 apogee_alt                : Apogee altitude [m] (type:float)
                 min_pressure              : Apogee pressure - Digital barometer [Pa] (type:float)
                 ada_min_pressure          : Apogee pressure - ADA filtered [Pa] (type:float)
-                dpl_vane_max_pressure        : Max pressure in the deployment bay during drogue deployment [Pa] (type:float)
+                dpl_bay_max_pressure        : Max pressure in the deployment bay during drogue deployment [Pa] (type:float)
                 cpu_load                  : CPU load in percentage (type:float)
                 free_heap                 : Amount of available heap in memory (type:uint32_t)
+                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+                log_good                  : 0 if log failed, 1 otherwise (type:int32_t)
+                payload_board_state        : Main board fmm state (type:uint8_t)
+                motor_board_state         : Motor board fmm state (type:uint8_t)
+                payload_can_status        : Main CAN status (type:uint8_t)
+                motor_can_status          : Motor CAN status (type:uint8_t)
+                rig_can_status            : RIG CAN status (type:uint8_t)
+                hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
 
                 '''
-                return self.send(self.rocket_stats_tm_encode(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), force_mavlink1=force_mavlink1)
+                return self.send(self.rocket_stats_tm_encode(liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_bay_max_pressure, cpu_load, free_heap, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, hil_state), force_mavlink1=force_mavlink1)
 
-        def payload_stats_tm_encode(self, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap):
+        def payload_stats_tm_encode(self, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state):
                 '''
                 Low Rate Telemetry
 
@@ -4936,11 +5132,19 @@ class MAVLink(object):
                 min_pressure              : Apogee pressure - Digital barometer [Pa] (type:float)
                 cpu_load                  : CPU load in percentage (type:float)
                 free_heap                 : Amount of available heap in memory (type:uint32_t)
+                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+                log_good                  : 0 if log failed, 1 otherwise (type:int32_t)
+                main_board_state          : Main board fmm state (type:uint8_t)
+                motor_board_state         : Motor board fmm state (type:uint8_t)
+                main_can_status           : Main CAN status (type:uint8_t)
+                motor_can_status          : Motor CAN status (type:uint8_t)
+                rig_can_status            : RIG CAN status (type:uint8_t)
+                hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
 
                 '''
-                return MAVLink_payload_stats_tm_message(liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap)
+                return MAVLink_payload_stats_tm_message(liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state)
 
-        def payload_stats_tm_send(self, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, force_mavlink1=False):
+        def payload_stats_tm_send(self, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state, force_mavlink1=False):
                 '''
                 Low Rate Telemetry
 
@@ -4959,11 +5163,19 @@ class MAVLink(object):
                 min_pressure              : Apogee pressure - Digital barometer [Pa] (type:float)
                 cpu_load                  : CPU load in percentage (type:float)
                 free_heap                 : Amount of available heap in memory (type:uint32_t)
+                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+                log_good                  : 0 if log failed, 1 otherwise (type:int32_t)
+                main_board_state          : Main board fmm state (type:uint8_t)
+                motor_board_state         : Motor board fmm state (type:uint8_t)
+                main_can_status           : Main CAN status (type:uint8_t)
+                motor_can_status          : Motor CAN status (type:uint8_t)
+                rig_can_status            : RIG CAN status (type:uint8_t)
+                hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
 
                 '''
-                return self.send(self.payload_stats_tm_encode(liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap), force_mavlink1=force_mavlink1)
+                return self.send(self.payload_stats_tm_encode(liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state), force_mavlink1=force_mavlink1)
 
-        def gse_tm_encode(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status):
+        def gse_tm_encode(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, arming_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good):
                 '''
                 Ground Segment Equipment telemetry
 
@@ -4972,24 +5184,30 @@ class MAVLink(object):
                 loadcell_vessel           : External tank weight [kg] (type:float)
                 filling_pressure          : Refueling line pressure [Bar] (type:float)
                 vessel_pressure           : Vessel tank pressure [Bar] (type:float)
-                arming_state              : 1 If the rocket is armed (type:uint8_t)
                 filling_valve_state        : 1 If the filling valve is open (type:uint8_t)
                 venting_valve_state        : 1 If the venting valve is open (type:uint8_t)
                 release_valve_state        : 1 If the release valve is open (type:uint8_t)
                 main_valve_state          : 1 If the main valve is open (type:uint8_t)
                 nitrogen_valve_state        : 1 If the nitrogen valve is open (type:uint8_t)
                 gmm_state                 : State of the GroundModeManager (type:uint8_t)
-                tars_state                : 1 If the TARS algorithm is running (type:uint8_t)
+                tars_state                : State of Tars (type:uint8_t)
+                arming_state              : Arming state (1 if armed, 0 otherwise) (type:uint8_t)
                 battery_voltage           : Battery voltage (type:float)
-                current_consumption        : RIG current (type:float)
-                main_board_status         : MAIN board status [0: not present, 1: online, 2: armed] (type:uint8_t)
-                payload_board_status        : PAYLOAD board status [0: not present, 1: online, 2: armed] (type:uint8_t)
-                motor_board_status        : MOTOR board status [0: not present, 1: online, 2: armed] (type:uint8_t)
+                current_consumption        : RIG current [A] (type:float)
+                umbilical_current_consumption        : Umbilical current [A] (type:float)
+                main_board_state          : Main board fmm state (type:uint8_t)
+                payload_board_state        : Payload board fmm state (type:uint8_t)
+                motor_board_state         : Motor board fmm state (type:uint8_t)
+                main_can_status           : Main CAN status (type:uint8_t)
+                payload_can_status        : Payload CAN status (type:uint8_t)
+                motor_can_status          : Motor CAN status (type:uint8_t)
+                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+                log_good                  : 0 if log failed, 1 otherwise (type:int32_t)
 
                 '''
-                return MAVLink_gse_tm_message(timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status)
+                return MAVLink_gse_tm_message(timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, arming_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good)
 
-        def gse_tm_send(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status, force_mavlink1=False):
+        def gse_tm_send(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, arming_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good, force_mavlink1=False):
                 '''
                 Ground Segment Equipment telemetry
 
@@ -4998,24 +5216,30 @@ class MAVLink(object):
                 loadcell_vessel           : External tank weight [kg] (type:float)
                 filling_pressure          : Refueling line pressure [Bar] (type:float)
                 vessel_pressure           : Vessel tank pressure [Bar] (type:float)
-                arming_state              : 1 If the rocket is armed (type:uint8_t)
                 filling_valve_state        : 1 If the filling valve is open (type:uint8_t)
                 venting_valve_state        : 1 If the venting valve is open (type:uint8_t)
                 release_valve_state        : 1 If the release valve is open (type:uint8_t)
                 main_valve_state          : 1 If the main valve is open (type:uint8_t)
                 nitrogen_valve_state        : 1 If the nitrogen valve is open (type:uint8_t)
                 gmm_state                 : State of the GroundModeManager (type:uint8_t)
-                tars_state                : 1 If the TARS algorithm is running (type:uint8_t)
+                tars_state                : State of Tars (type:uint8_t)
+                arming_state              : Arming state (1 if armed, 0 otherwise) (type:uint8_t)
                 battery_voltage           : Battery voltage (type:float)
-                current_consumption        : RIG current (type:float)
-                main_board_status         : MAIN board status [0: not present, 1: online, 2: armed] (type:uint8_t)
-                payload_board_status        : PAYLOAD board status [0: not present, 1: online, 2: armed] (type:uint8_t)
-                motor_board_status        : MOTOR board status [0: not present, 1: online, 2: armed] (type:uint8_t)
+                current_consumption        : RIG current [A] (type:float)
+                umbilical_current_consumption        : Umbilical current [A] (type:float)
+                main_board_state          : Main board fmm state (type:uint8_t)
+                payload_board_state        : Payload board fmm state (type:uint8_t)
+                motor_board_state         : Motor board fmm state (type:uint8_t)
+                main_can_status           : Main CAN status (type:uint8_t)
+                payload_can_status        : Payload CAN status (type:uint8_t)
+                motor_can_status          : Motor CAN status (type:uint8_t)
+                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+                log_good                  : 0 if log failed, 1 otherwise (type:int32_t)
 
                 '''
-                return self.send(self.gse_tm_encode(timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status), force_mavlink1=force_mavlink1)
+                return self.send(self.gse_tm_encode(timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, arming_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good), force_mavlink1=force_mavlink1)
 
-        def motor_tm_encode(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, current_consumption):
+        def motor_tm_encode(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, log_good, hil_state):
                 '''
                 Motor rocket telemetry
 
@@ -5027,12 +5251,14 @@ class MAVLink(object):
                 main_valve_state          : 1 If the main valve is open (type:uint8_t)
                 venting_valve_state        : 1 If the venting valve is open (type:uint8_t)
                 battery_voltage           : Battery voltage [V] (type:float)
-                current_consumption        : Current drained from the battery [A] (type:float)
+                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+                log_good                  : 0 if log failed, 1 otherwise (type:int32_t)
+                hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
 
                 '''
-                return MAVLink_motor_tm_message(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, current_consumption)
+                return MAVLink_motor_tm_message(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, log_good, hil_state)
 
-        def motor_tm_send(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, current_consumption, force_mavlink1=False):
+        def motor_tm_send(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, log_good, hil_state, force_mavlink1=False):
                 '''
                 Motor rocket telemetry
 
@@ -5044,8 +5270,10 @@ class MAVLink(object):
                 main_valve_state          : 1 If the main valve is open (type:uint8_t)
                 venting_valve_state        : 1 If the venting valve is open (type:uint8_t)
                 battery_voltage           : Battery voltage [V] (type:float)
-                current_consumption        : Current drained from the battery [A] (type:float)
+                log_number                : Currently active log file, -1 if the logger is inactive (type:int16_t)
+                log_good                  : 0 if log failed, 1 otherwise (type:int32_t)
+                hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
 
                 '''
-                return self.send(self.motor_tm_encode(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, current_consumption), force_mavlink1=force_mavlink1)
+                return self.send(self.motor_tm_encode(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, log_good, hil_state), force_mavlink1=force_mavlink1)
 
diff --git a/mavlink_lib/lyra/lyra.h b/mavlink_lib/lyra/lyra.h
index d33874abe17cf7dc1e4c74cef686c6a3b2a9c07d..f938e5aac62a9912f7f40f77057a9730f9f5025f 100644
--- a/mavlink_lib/lyra/lyra.h
+++ b/mavlink_lib/lyra/lyra.h
@@ -11,7 +11,7 @@
 #endif
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -9164606166033445911
+#define MAVLINK_THIS_XML_HASH 4317817575156074154
 
 #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, 5, 5, 4, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 60, 32, 32, 32, 32, 56, 21, 5, 19, 36, 36, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 52, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 86, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 46, 28, 27, 53, 77, 29, 176, 163, 92, 76, 43, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 16, 8, 2, 4, 8, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 7, 4, 4, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 5, 12, 12, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 4, 4, 74, 64, 32, 60, 32, 32, 32, 32, 56, 22, 5, 19, 36, 36, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 46, 28, 20, 44, 53, 77, 29, 167, 159, 104, 88, 56, 37, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #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, 180, 246, 167, 84, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 57, 72, 87, 229, 245, 212, 140, 148, 6, 155, 87, 255, 9, 68, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 117, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 202, 164, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 242, 142, 108, 133, 234, 66, 11, 214, 84, 245, 115, 81, 89, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 226, 160, 113, 38, 71, 168, 67, 218, 44, 81, 181, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 110, 22, 65, 79, 167, 84, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 180, 246, 173, 183, 220, 181, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 251, 51, 57, 72, 87, 229, 245, 212, 140, 148, 6, 165, 87, 255, 9, 68, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 48, 142, 108, 39, 19, 234, 66, 11, 52, 59, 46, 64, 33, 67, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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"
@@ -53,22 +53,21 @@ typedef enum SysIDs
 typedef enum SystemTMList
 {
    MAV_SYS_ID=1, /* State of init results about system hardware/software components | */
-   MAV_FSM_ID=2, /* States of all On-Board FSMs | */
-   MAV_PIN_OBS_ID=3, /* Pin observer data | */
-   MAV_LOGGER_ID=4, /* SD Logger stats | */
-   MAV_MAVLINK_STATS=5, /* Mavlink driver stats | */
-   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_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 | */
-   MAV_REGISTRY_ID=22, /* Command to fetch all registry keys | */
-   SystemTMList_ENUM_END=23, /*  | */
+   MAV_PIN_OBS_ID=2, /* Pin observer data | */
+   MAV_LOGGER_ID=3, /* SD Logger stats | */
+   MAV_MAVLINK_STATS_ID=4, /* Mavlink driver stats | */
+   MAV_TASK_STATS_ID=5, /* Task scheduler statistics answer: n mavlink messages where n is the number of tasks | */
+   MAV_ADA_ID=6, /* ADA Status | */
+   MAV_NAS_ID=7, /* NavigationSystem data | */
+   MAV_MEA_ID=8, /* MEA Status | */
+   MAV_CAN_STATS_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_REGISTRY_ID=15, /* Command to fetch all registry keys | */
+   SystemTMList_ENUM_END=16, /*  | */
 } SystemTMList;
 #endif
 
@@ -77,34 +76,38 @@ typedef enum SystemTMList
 #define HAVE_ENUM_SensorsTMList
 typedef enum SensorsTMList
 {
-   MAV_GPS_ID=1, /* GPS data | */
-   MAV_BMX160_ID=2, /* BMX160 IMU data | */
-   MAV_VN100_ID=3, /* VN100 IMU data | */
-   MAV_MPU9250_ID=4, /* MPU9250 IMU data | */
-   MAV_ADS_ID=5, /* ADS 8 channel ADC data | */
-   MAV_MS5803_ID=6, /* MS5803 barometer data | */
-   MAV_BME280_ID=7, /* BME280 barometer data | */
-   MAV_CURRENT_SENSE_ID=8, /* Electrical current sensors data | */
-   MAV_LIS3MDL_ID=9, /* LIS3MDL compass data | */
-   MAV_DPL_PRESS_ID=10, /* Deployment pressure data | */
-   MAV_STATIC_PRESS_ID=11, /* Static pressure data | */
-   MAV_PITOT_PRESS_ID=12, /* Pitot pressure data | */
-   MAV_BATTERY_VOLTAGE_ID=13, /* Battery voltage data | */
-   MAV_LOAD_CELL_ID=14, /* Load cell data | */
-   MAV_FILLING_PRESS_ID=15, /* Filling line pressure | */
-   MAV_TANK_TOP_PRESS_ID=16, /* Top tank pressure | */
-   MAV_TANK_BOTTOM_PRESS_ID=17, /* Bottom tank pressure | */
-   MAV_TANK_TEMP_ID=18, /* Tank temperature | */
-   MAV_COMBUSTION_PRESS_ID=19, /* Combustion chamber pressure | */
-   MAV_VESSEL_PRESS_ID=20, /* Vessel pressure | */
-   MAV_LOAD_CELL_VESSEL_ID=21, /* Vessel tank weight | */
-   MAV_LOAD_CELL_TANK_ID=22, /* Tank weight | */
-   MAV_LIS2MDL_ID=23, /* Magnetometer data | */
-   MAV_LPS28DFW_ID=24, /* Pressure sensor data | */
-   MAV_LSM6DSRX_ID=25, /* IMU data | */
-   MAV_H3LIS331DL_ID=26, /* 400G accelerometer | */
-   MAV_LPS22DF_ID=27, /* Pressure sensor data | */
-   SensorsTMList_ENUM_END=28, /*  | */
+   MAV_BMX160_ID=1, /* BMX160 IMU data | */
+   MAV_VN100_ID=2, /* VN100 IMU data | */
+   MAV_MPU9250_ID=3, /* MPU9250 IMU data | */
+   MAV_ADS131M08_ID=4, /* ADS 8 channel ADC data | */
+   MAV_MS5803_ID=5, /* MS5803 barometer data | */
+   MAV_BME280_ID=6, /* BME280 barometer data | */
+   MAV_LIS3MDL_ID=7, /* LIS3MDL compass data | */
+   MAV_LIS2MDL_ID=8, /* Magnetometer data | */
+   MAV_LPS28DFW_ID=9, /* Pressure sensor data | */
+   MAV_LSM6DSRX_ID=10, /* IMU data | */
+   MAV_H3LIS331DL_ID=11, /* 400G accelerometer | */
+   MAV_LPS22DF_ID=12, /* Pressure sensor data | */
+   MAV_GPS_ID=13, /* GPS data | */
+   MAV_CURRENT_SENSE_ID=14, /* Electrical current sensors data | */
+   MAV_BATTERY_VOLTAGE_ID=15, /* Battery voltage data | */
+   MAV_ROTATED_IMU_ID=16, /* Load cell data | */
+   MAV_DPL_PRESS_ID=17, /* Deployment pressure data | */
+   MAV_STATIC_PRESS_ID=18, /* Static pressure data | */
+   MAV_BACKUP_STATIC_PRESS_ID=19, /* Static pressure data | */
+   MAV_STATIC_PITOT_PRESS_ID=20, /* Pitot pressure data | */
+   MAV_TOTAL_PITOT_PRESS_ID=21, /* Pitot pressure data | */
+   MAV_DYNAMIC_PITOT_PRESS_ID=22, /* Pitot pressure data | */
+   MAV_LOAD_CELL_ID=23, /* Load cell data | */
+   MAV_TANK_TOP_PRESS_ID=24, /* Top tank pressure | */
+   MAV_TANK_BOTTOM_PRESS_ID=25, /* Bottom tank pressure | */
+   MAV_TANK_TEMP_ID=26, /* Tank temperature | */
+   MAV_COMBUSTION_PRESS_ID=27, /* Combustion chamber pressure | */
+   MAV_FILLING_PRESS_ID=28, /* Filling line pressure | */
+   MAV_VESSEL_PRESS_ID=29, /* Vessel pressure | */
+   MAV_LOAD_CELL_VESSEL_ID=30, /* Vessel tank weight | */
+   MAV_LOAD_CELL_TANK_ID=31, /* Tank weight | */
+   SensorsTMList_ENUM_END=32, /*  | */
 } SensorsTMList;
 #endif
 
@@ -119,10 +122,10 @@ typedef enum MavCommandList
    MAV_CMD_SAVE_CALIBRATION=4, /* Command to save the current calibration into a file | */
    MAV_CMD_FORCE_INIT=5, /* Command to init the rocket | */
    MAV_CMD_FORCE_LAUNCH=6, /* Command to force the launch state on the rocket | */
-   MAV_CMD_FORCE_LANDING=7, /* Command to communicate the end of the mission and close the file descriptors in the SD card | */
-   MAV_CMD_FORCE_APOGEE=8, /* Command to trigger the apogee event | */
-   MAV_CMD_FORCE_EXPULSION=9, /* Command to open the nosecone | */
-   MAV_CMD_FORCE_DEPLOYMENT=10, /* Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially | */
+   MAV_CMD_FORCE_ENGINE_SHUTDOWN=7, /* Command to trigger engine shutdown | */
+   MAV_CMD_FORCE_EXPULSION=8, /* Command to trigger nosecone expulsion | */
+   MAV_CMD_FORCE_DEPLOYMENT=9, /* Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially | */
+   MAV_CMD_FORCE_LANDING=10, /* Command to communicate the end of the mission and close the file descriptors in the SD card | */
    MAV_CMD_START_LOGGING=11, /* Command to enable sensor logging | */
    MAV_CMD_STOP_LOGGING=12, /* Command to permanently close the log file | */
    MAV_CMD_FORCE_REBOOT=13, /* Command to reset the board from test status | */
@@ -134,11 +137,12 @@ typedef enum MavCommandList
    MAV_CMD_REGISTRY_LOAD=19, /* Command to reload the registry from memory | */
    MAV_CMD_REGISTRY_SAVE=20, /* Command to commit the registry to memory | */
    MAV_CMD_REGISTRY_CLEAR=21, /* Command to clear the registry | */
-   MavCommandList_ENUM_END=22, /*  | */
+   MAV_CMD_ENTER_HIL=22, /* Command to enter HIL mode at next reboot | */
+   MavCommandList_ENUM_END=23, /*  | */
 } MavCommandList;
 #endif
 
-/** @brief Enum of all the servos used on Gemini */
+/** @brief Enum of all the servos */
 #ifndef HAVE_ENUM_ServosList
 #define HAVE_ENUM_ServosList
 typedef enum ServosList
@@ -156,7 +160,7 @@ typedef enum ServosList
 } ServosList;
 #endif
 
-/** @brief Enum of all the steppers used on Gemini systems */
+/** @brief Enum of all the steppers */
 #ifndef HAVE_ENUM_StepperList
 #define HAVE_ENUM_StepperList
 typedef enum StepperList
@@ -167,16 +171,14 @@ typedef enum StepperList
 } StepperList;
 #endif
 
-/** @brief Enum of all the pins used on Gemini */
+/** @brief Enum of all the pins */
 #ifndef HAVE_ENUM_PinsList
 #define HAVE_ENUM_PinsList
 typedef enum PinsList
 {
-   LAUNCH_PIN=1, /*  | */
+   RAMP_PIN=1, /*  | */
    NOSECONE_PIN=2, /*  | */
-   DEPLOYMENT_PIN=3, /*  | */
-   QUICK_CONNECTOR_PIN=4, /*  | */
-   PinsList_ENUM_END=5, /*  | */
+   PinsList_ENUM_END=3, /*  | */
 } PinsList;
 #endif
 
@@ -198,11 +200,12 @@ typedef enum PinsList
 #include "./mavlink_msg_sensor_tm_request_tc.h"
 #include "./mavlink_msg_servo_tm_request_tc.h"
 #include "./mavlink_msg_set_servo_angle_tc.h"
-#include "./mavlink_msg_wiggle_servo_tc.h"
 #include "./mavlink_msg_reset_servo_tc.h"
+#include "./mavlink_msg_wiggle_servo_tc.h"
 #include "./mavlink_msg_set_reference_altitude_tc.h"
 #include "./mavlink_msg_set_reference_temperature_tc.h"
 #include "./mavlink_msg_set_orientation_tc.h"
+#include "./mavlink_msg_set_orientation_quat_tc.h"
 #include "./mavlink_msg_set_coordinates_tc.h"
 #include "./mavlink_msg_raw_event_tc.h"
 #include "./mavlink_msg_set_deployment_altitude_tc.h"
@@ -212,12 +215,17 @@ typedef enum PinsList
 #include "./mavlink_msg_set_valve_maximum_aperture_tc.h"
 #include "./mavlink_msg_conrig_state_tc.h"
 #include "./mavlink_msg_set_ignition_time_tc.h"
-#include "./mavlink_msg_set_stepper_angle_tc.h"
-#include "./mavlink_msg_set_stepper_steps_tc.h"
 #include "./mavlink_msg_set_nitrogen_time_tc.h"
 #include "./mavlink_msg_set_cooling_time_tc.h"
+#include "./mavlink_msg_set_stepper_angle_tc.h"
+#include "./mavlink_msg_set_stepper_steps_tc.h"
+#include "./mavlink_msg_set_stepper_multiplier_tc.h"
+#include "./mavlink_msg_set_antenna_coordinates_arp_tc.h"
+#include "./mavlink_msg_set_rocket_coordinates_arp_tc.h"
+#include "./mavlink_msg_arp_command_tc.h"
 #include "./mavlink_msg_ack_tm.h"
 #include "./mavlink_msg_nack_tm.h"
+#include "./mavlink_msg_wack_tm.h"
 #include "./mavlink_msg_gps_tm.h"
 #include "./mavlink_msg_imu_tm.h"
 #include "./mavlink_msg_pressure_tm.h"
@@ -233,14 +241,11 @@ typedef enum PinsList
 #include "./mavlink_msg_registry_float_tm.h"
 #include "./mavlink_msg_registry_int_tm.h"
 #include "./mavlink_msg_registry_coord_tm.h"
-#include "./mavlink_msg_receiver_tm.h"
 #include "./mavlink_msg_arp_tm.h"
-#include "./mavlink_msg_set_antenna_coordinates_arp_tc.h"
-#include "./mavlink_msg_set_rocket_coordinates_arp_tc.h"
 #include "./mavlink_msg_sys_tm.h"
-#include "./mavlink_msg_fsm_tm.h"
 #include "./mavlink_msg_logger_tm.h"
 #include "./mavlink_msg_mavlink_stats_tm.h"
+#include "./mavlink_msg_can_stats_tm.h"
 #include "./mavlink_msg_task_stats_tm.h"
 #include "./mavlink_msg_ada_tm.h"
 #include "./mavlink_msg_nas_tm.h"
@@ -256,11 +261,11 @@ typedef enum PinsList
 
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -9164606166033445911
+#define MAVLINK_THIS_XML_HASH 4317817575156074154
 
 #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, MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC, MAVLINK_MESSAGE_INFO_SET_NITROGEN_TIME_TC, MAVLINK_MESSAGE_INFO_SET_COOLING_TIME_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, MAVLINK_MESSAGE_INFO_REGISTRY_FLOAT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_INT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_COORD_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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}}}, MAVLINK_MESSAGE_INFO_ARP_TM, MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, 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 }, { "ARP_TM", 169 }, { "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 }, { "REGISTRY_COORD_TM", 116 }, { "REGISTRY_FLOAT_TM", 114 }, { "REGISTRY_INT_TM", 115 }, { "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_ANTENNA_COORDINATES_ARP_TC", 170 }, { "SET_ATOMIC_VALVE_TIMING_TC", 17 }, { "SET_COOLING_TIME_TC", 24 }, { "SET_COORDINATES_TC", 12 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 14 }, { "SET_IGNITION_TIME_TC", 20 }, { "SET_NITROGEN_TIME_TC", 23 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_ROCKET_COORDINATES_ARP_TC", 171 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_STEPPER_ANGLE_TC", 21 }, { "SET_STEPPER_STEPS_TC", 22 }, { "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_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_QUAT_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, MAVLINK_MESSAGE_INFO_SET_NITROGEN_TIME_TC, MAVLINK_MESSAGE_INFO_SET_COOLING_TIME_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_MULTIPLIER_TC, MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_ARP_COMMAND_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_WACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, MAVLINK_MESSAGE_INFO_REGISTRY_FLOAT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_INT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_COORD_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ARP_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_CAN_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_MEA_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
+# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 106 }, { "ARP_COMMAND_TC", 65 }, { "ARP_TM", 150 }, { "ATTITUDE_TM", 111 }, { "CAN_STATS_TM", 203 }, { "COMMAND_TC", 2 }, { "CONRIG_STATE_TC", 32 }, { "CURRENT_TM", 108 }, { "GPS_TM", 103 }, { "GSE_TM", 212 }, { "IMU_TM", 104 }, { "LOAD_TM", 110 }, { "LOGGER_TM", 201 }, { "MAVLINK_STATS_TM", 202 }, { "MEA_TM", 207 }, { "MOTOR_TM", 213 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 114 }, { "PRESSURE_TM", 105 }, { "RAW_EVENT_TC", 14 }, { "REGISTRY_COORD_TM", 117 }, { "REGISTRY_FLOAT_TM", 115 }, { "REGISTRY_INT_TM", 116 }, { "RESET_SERVO_TC", 7 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 112 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 113 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 17 }, { "SET_ANTENNA_COORDINATES_ARP_TC", 63 }, { "SET_ATOMIC_VALVE_TIMING_TC", 30 }, { "SET_COOLING_TIME_TC", 35 }, { "SET_COORDINATES_TC", 13 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 15 }, { "SET_IGNITION_TIME_TC", 33 }, { "SET_NITROGEN_TIME_TC", 34 }, { "SET_ORIENTATION_QUAT_TC", 12 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_ROCKET_COORDINATES_ARP_TC", 64 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_STEPPER_ANGLE_TC", 60 }, { "SET_STEPPER_MULTIPLIER_TC", 62 }, { "SET_STEPPER_STEPS_TC", 61 }, { "SET_TARGET_COORDINATES_TC", 16 }, { "SET_VALVE_MAXIMUM_APERTURE_TC", 31 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 109 }, { "VOLTAGE_TM", 107 }, { "WACK_TM", 102 }, { "WIGGLE_SERVO_TC", 8 }}
 # if MAVLINK_COMMAND_24BIT
 #  include "../mavlink_get_info.h"
 # endif
diff --git a/mavlink_lib/lyra/mavlink.h b/mavlink_lib/lyra/mavlink.h
index 3a7533da51c415914add0dc022ab334ae6d0af8f..0f32071e03b0a7fc527179b21f669b3a7f30cc32 100644
--- a/mavlink_lib/lyra/mavlink.h
+++ b/mavlink_lib/lyra/mavlink.h
@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -9164606166033445911
+#define MAVLINK_PRIMARY_XML_HASH 4317817575156074154
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 254
diff --git a/mavlink_lib/lyra/mavlink_msg_adc_tm.h b/mavlink_lib/lyra/mavlink_msg_adc_tm.h
index 04c7612852769618318043c1a36059b224ba9a18..ddd0f2ef7947c235fd4f2bc7d7259db63d6ed580 100644
--- a/mavlink_lib/lyra/mavlink_msg_adc_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_adc_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE ADC_TM PACKING
 
-#define MAVLINK_MSG_ID_ADC_TM 105
+#define MAVLINK_MSG_ID_ADC_TM 106
 
 
 typedef struct __mavlink_adc_tm_t {
@@ -19,17 +19,17 @@ typedef struct __mavlink_adc_tm_t {
 
 #define MAVLINK_MSG_ID_ADC_TM_LEN 60
 #define MAVLINK_MSG_ID_ADC_TM_MIN_LEN 60
-#define MAVLINK_MSG_ID_105_LEN 60
-#define MAVLINK_MSG_ID_105_MIN_LEN 60
+#define MAVLINK_MSG_ID_106_LEN 60
+#define MAVLINK_MSG_ID_106_MIN_LEN 60
 
 #define MAVLINK_MSG_ID_ADC_TM_CRC 229
-#define MAVLINK_MSG_ID_105_CRC 229
+#define MAVLINK_MSG_ID_106_CRC 229
 
 #define MAVLINK_MSG_ADC_TM_FIELD_SENSOR_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_ADC_TM { \
-    105, \
+    106, \
     "ADC_TM", \
     10, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_arp_command_tc.h b/mavlink_lib/lyra/mavlink_msg_arp_command_tc.h
new file mode 100644
index 0000000000000000000000000000000000000000..30decba2403769beb9b8af05452b3dc48469a6b4
--- /dev/null
+++ b/mavlink_lib/lyra/mavlink_msg_arp_command_tc.h
@@ -0,0 +1,213 @@
+#pragma once
+// MESSAGE ARP_COMMAND_TC PACKING
+
+#define MAVLINK_MSG_ID_ARP_COMMAND_TC 65
+
+
+typedef struct __mavlink_arp_command_tc_t {
+ uint8_t command_id; /*<  A member of the MavArpCommandList enum*/
+} mavlink_arp_command_tc_t;
+
+#define MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN 1
+#define MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN 1
+#define MAVLINK_MSG_ID_65_LEN 1
+#define MAVLINK_MSG_ID_65_MIN_LEN 1
+
+#define MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC 181
+#define MAVLINK_MSG_ID_65_CRC 181
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ARP_COMMAND_TC { \
+    65, \
+    "ARP_COMMAND_TC", \
+    1, \
+    {  { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_arp_command_tc_t, command_id) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ARP_COMMAND_TC { \
+    "ARP_COMMAND_TC", \
+    1, \
+    {  { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_arp_command_tc_t, command_id) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a arp_command_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param command_id  A member of the MavArpCommandList enum
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_arp_command_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint8_t command_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN];
+    _mav_put_uint8_t(buf, 0, command_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN);
+#else
+    mavlink_arp_command_tc_t packet;
+    packet.command_id = command_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ARP_COMMAND_TC;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC);
+}
+
+/**
+ * @brief Pack a arp_command_tc message 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 command_id  A member of the MavArpCommandList enum
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_arp_command_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint8_t command_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN];
+    _mav_put_uint8_t(buf, 0, command_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN);
+#else
+    mavlink_arp_command_tc_t packet;
+    packet.command_id = command_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_ARP_COMMAND_TC;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC);
+}
+
+/**
+ * @brief Encode a arp_command_tc 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 arp_command_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_arp_command_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_arp_command_tc_t* arp_command_tc)
+{
+    return mavlink_msg_arp_command_tc_pack(system_id, component_id, msg, arp_command_tc->command_id);
+}
+
+/**
+ * @brief Encode a arp_command_tc 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 arp_command_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_arp_command_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_arp_command_tc_t* arp_command_tc)
+{
+    return mavlink_msg_arp_command_tc_pack_chan(system_id, component_id, chan, msg, arp_command_tc->command_id);
+}
+
+/**
+ * @brief Send a arp_command_tc message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param command_id  A member of the MavArpCommandList enum
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_arp_command_tc_send(mavlink_channel_t chan, uint8_t command_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN];
+    _mav_put_uint8_t(buf, 0, command_id);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_COMMAND_TC, buf, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC);
+#else
+    mavlink_arp_command_tc_t packet;
+    packet.command_id = command_id;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_COMMAND_TC, (const char *)&packet, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC);
+#endif
+}
+
+/**
+ * @brief Send a arp_command_tc message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_arp_command_tc_send_struct(mavlink_channel_t chan, const mavlink_arp_command_tc_t* arp_command_tc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_arp_command_tc_send(chan, arp_command_tc->command_id);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_COMMAND_TC, (const char *)arp_command_tc, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ARP_COMMAND_TC_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_arp_command_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t command_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint8_t(buf, 0, command_id);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_COMMAND_TC, buf, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC);
+#else
+    mavlink_arp_command_tc_t *packet = (mavlink_arp_command_tc_t *)msgbuf;
+    packet->command_id = command_id;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_COMMAND_TC, (const char *)packet, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ARP_COMMAND_TC UNPACKING
+
+
+/**
+ * @brief Get field command_id from arp_command_tc message
+ *
+ * @return  A member of the MavArpCommandList enum
+ */
+static inline uint8_t mavlink_msg_arp_command_tc_get_command_id(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  0);
+}
+
+/**
+ * @brief Decode a arp_command_tc message into a struct
+ *
+ * @param msg The message to decode
+ * @param arp_command_tc C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_arp_command_tc_decode(const mavlink_message_t* msg, mavlink_arp_command_tc_t* arp_command_tc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    arp_command_tc->command_id = mavlink_msg_arp_command_tc_get_command_id(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN? msg->len : MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN;
+        memset(arp_command_tc, 0, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN);
+    memcpy(arp_command_tc, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/mavlink_lib/lyra/mavlink_msg_arp_tm.h b/mavlink_lib/lyra/mavlink_msg_arp_tm.h
index 0a20a8023588f8961ac5fdb386c407d53d138200..dc4045d218fe505f05fce9d5d18e940f32bb8a7e 100644
--- a/mavlink_lib/lyra/mavlink_msg_arp_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_arp_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE ARP_TM PACKING
 
-#define MAVLINK_MSG_ID_ARP_TM 169
+#define MAVLINK_MSG_ID_ARP_TM 150
 
 
 typedef struct __mavlink_arp_tm_t {
@@ -21,33 +21,40 @@ typedef struct __mavlink_arp_tm_t {
  float gps_longitude; /*< [deg] Longitude*/
  float gps_height; /*< [m] Altitude*/
  float main_rx_rssi; /*< [dBm] Receive RSSI*/
+ float payload_rx_rssi; /*< [dBm] Receive RSSI*/
  float battery_voltage; /*< [V] Battery voltage*/
  uint16_t main_packet_tx_error_count; /*<  Number of errors during send*/
  uint16_t main_tx_bitrate; /*< [b/s] Send bitrate*/
  uint16_t main_packet_rx_success_count; /*<  Number of succesfull received mavlink packets*/
  uint16_t main_packet_rx_drop_count; /*<  Number of dropped mavlink packets*/
  uint16_t main_rx_bitrate; /*< [b/s] Receive bitrate*/
+ uint16_t payload_packet_tx_error_count; /*<  Number of errors during send*/
+ uint16_t payload_tx_bitrate; /*< [b/s] Send bitrate*/
+ uint16_t payload_packet_rx_success_count; /*<  Number of succesfull received mavlink packets*/
+ uint16_t payload_packet_rx_drop_count; /*<  Number of dropped mavlink packets*/
+ uint16_t payload_rx_bitrate; /*< [b/s] Receive bitrate*/
  uint8_t gps_fix; /*<  Wether the GPS has a FIX*/
  uint8_t main_radio_present; /*<  Boolean indicating the presence of the main radio*/
+ uint8_t payload_radio_present; /*<  Boolean indicating the presence of the payload radio*/
  uint8_t ethernet_present; /*<  Boolean indicating the presence of the ethernet module*/
  uint8_t ethernet_status; /*<  Status flag indicating the status of the ethernet PHY*/
 } mavlink_arp_tm_t;
 
-#define MAVLINK_MSG_ID_ARP_TM_LEN 86
-#define MAVLINK_MSG_ID_ARP_TM_MIN_LEN 86
-#define MAVLINK_MSG_ID_169_LEN 86
-#define MAVLINK_MSG_ID_169_MIN_LEN 86
+#define MAVLINK_MSG_ID_ARP_TM_LEN 101
+#define MAVLINK_MSG_ID_ARP_TM_MIN_LEN 101
+#define MAVLINK_MSG_ID_150_LEN 101
+#define MAVLINK_MSG_ID_150_MIN_LEN 101
 
-#define MAVLINK_MSG_ID_ARP_TM_CRC 2
-#define MAVLINK_MSG_ID_169_CRC 2
+#define MAVLINK_MSG_ID_ARP_TM_CRC 22
+#define MAVLINK_MSG_ID_150_CRC 22
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_ARP_TM { \
-    169, \
+    150, \
     "ARP_TM", \
-    26, \
+    33, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_arp_tm_t, timestamp) }, \
          { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_arp_tm_t, yaw) }, \
          { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_arp_tm_t, pitch) }, \
@@ -63,23 +70,30 @@ typedef struct __mavlink_arp_tm_t {
          { "gps_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_arp_tm_t, gps_latitude) }, \
          { "gps_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_arp_tm_t, gps_longitude) }, \
          { "gps_height", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_arp_tm_t, gps_height) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_arp_tm_t, gps_fix) }, \
-         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_arp_tm_t, main_radio_present) }, \
-         { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 72, offsetof(mavlink_arp_tm_t, main_packet_tx_error_count) }, \
-         { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 74, offsetof(mavlink_arp_tm_t, main_tx_bitrate) }, \
-         { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 76, offsetof(mavlink_arp_tm_t, main_packet_rx_success_count) }, \
-         { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_arp_tm_t, main_packet_rx_drop_count) }, \
-         { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_arp_tm_t, main_rx_bitrate) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 96, offsetof(mavlink_arp_tm_t, gps_fix) }, \
+         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 97, offsetof(mavlink_arp_tm_t, main_radio_present) }, \
+         { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 76, offsetof(mavlink_arp_tm_t, main_packet_tx_error_count) }, \
+         { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_arp_tm_t, main_tx_bitrate) }, \
+         { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_arp_tm_t, main_packet_rx_success_count) }, \
+         { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 82, offsetof(mavlink_arp_tm_t, main_packet_rx_drop_count) }, \
+         { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 84, offsetof(mavlink_arp_tm_t, main_rx_bitrate) }, \
          { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_arp_tm_t, main_rx_rssi) }, \
-         { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 84, offsetof(mavlink_arp_tm_t, ethernet_present) }, \
-         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 85, offsetof(mavlink_arp_tm_t, ethernet_status) }, \
-         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_arp_tm_t, battery_voltage) }, \
+         { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 98, offsetof(mavlink_arp_tm_t, payload_radio_present) }, \
+         { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 86, offsetof(mavlink_arp_tm_t, payload_packet_tx_error_count) }, \
+         { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 88, offsetof(mavlink_arp_tm_t, payload_tx_bitrate) }, \
+         { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 90, offsetof(mavlink_arp_tm_t, payload_packet_rx_success_count) }, \
+         { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 92, offsetof(mavlink_arp_tm_t, payload_packet_rx_drop_count) }, \
+         { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 94, offsetof(mavlink_arp_tm_t, payload_rx_bitrate) }, \
+         { "payload_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_arp_tm_t, payload_rx_rssi) }, \
+         { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 99, offsetof(mavlink_arp_tm_t, ethernet_present) }, \
+         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 100, offsetof(mavlink_arp_tm_t, ethernet_status) }, \
+         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_arp_tm_t, battery_voltage) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_ARP_TM { \
     "ARP_TM", \
-    26, \
+    33, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_arp_tm_t, timestamp) }, \
          { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_arp_tm_t, yaw) }, \
          { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_arp_tm_t, pitch) }, \
@@ -95,17 +109,24 @@ typedef struct __mavlink_arp_tm_t {
          { "gps_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_arp_tm_t, gps_latitude) }, \
          { "gps_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_arp_tm_t, gps_longitude) }, \
          { "gps_height", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_arp_tm_t, gps_height) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_arp_tm_t, gps_fix) }, \
-         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_arp_tm_t, main_radio_present) }, \
-         { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 72, offsetof(mavlink_arp_tm_t, main_packet_tx_error_count) }, \
-         { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 74, offsetof(mavlink_arp_tm_t, main_tx_bitrate) }, \
-         { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 76, offsetof(mavlink_arp_tm_t, main_packet_rx_success_count) }, \
-         { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_arp_tm_t, main_packet_rx_drop_count) }, \
-         { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_arp_tm_t, main_rx_bitrate) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 96, offsetof(mavlink_arp_tm_t, gps_fix) }, \
+         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 97, offsetof(mavlink_arp_tm_t, main_radio_present) }, \
+         { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 76, offsetof(mavlink_arp_tm_t, main_packet_tx_error_count) }, \
+         { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_arp_tm_t, main_tx_bitrate) }, \
+         { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_arp_tm_t, main_packet_rx_success_count) }, \
+         { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 82, offsetof(mavlink_arp_tm_t, main_packet_rx_drop_count) }, \
+         { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 84, offsetof(mavlink_arp_tm_t, main_rx_bitrate) }, \
          { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_arp_tm_t, main_rx_rssi) }, \
-         { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 84, offsetof(mavlink_arp_tm_t, ethernet_present) }, \
-         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 85, offsetof(mavlink_arp_tm_t, ethernet_status) }, \
-         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_arp_tm_t, battery_voltage) }, \
+         { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 98, offsetof(mavlink_arp_tm_t, payload_radio_present) }, \
+         { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 86, offsetof(mavlink_arp_tm_t, payload_packet_tx_error_count) }, \
+         { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 88, offsetof(mavlink_arp_tm_t, payload_tx_bitrate) }, \
+         { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 90, offsetof(mavlink_arp_tm_t, payload_packet_rx_success_count) }, \
+         { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 92, offsetof(mavlink_arp_tm_t, payload_packet_rx_drop_count) }, \
+         { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 94, offsetof(mavlink_arp_tm_t, payload_rx_bitrate) }, \
+         { "payload_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_arp_tm_t, payload_rx_rssi) }, \
+         { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 99, offsetof(mavlink_arp_tm_t, ethernet_present) }, \
+         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 100, offsetof(mavlink_arp_tm_t, ethernet_status) }, \
+         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_arp_tm_t, battery_voltage) }, \
          } \
 }
 #endif
@@ -139,13 +160,20 @@ typedef struct __mavlink_arp_tm_t {
  * @param main_packet_rx_drop_count  Number of dropped mavlink packets
  * @param main_rx_bitrate [b/s] Receive bitrate
  * @param main_rx_rssi [dBm] Receive RSSI
+ * @param payload_radio_present  Boolean indicating the presence of the payload radio
+ * @param payload_packet_tx_error_count  Number of errors during send
+ * @param payload_tx_bitrate [b/s] Send bitrate
+ * @param payload_packet_rx_success_count  Number of succesfull received mavlink packets
+ * @param payload_packet_rx_drop_count  Number of dropped mavlink packets
+ * @param payload_rx_bitrate [b/s] Receive bitrate
+ * @param payload_rx_rssi [dBm] Receive RSSI
  * @param ethernet_present  Boolean indicating the presence of the ethernet module
  * @param ethernet_status  Status flag indicating the status of the ethernet PHY
  * @param battery_voltage [V] Battery voltage
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
+                               uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
@@ -165,16 +193,23 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
     _mav_put_float(buf, 56, gps_longitude);
     _mav_put_float(buf, 60, gps_height);
     _mav_put_float(buf, 64, main_rx_rssi);
-    _mav_put_float(buf, 68, battery_voltage);
-    _mav_put_uint16_t(buf, 72, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 74, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 76, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 78, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 80, main_rx_bitrate);
-    _mav_put_uint8_t(buf, 82, gps_fix);
-    _mav_put_uint8_t(buf, 83, main_radio_present);
-    _mav_put_uint8_t(buf, 84, ethernet_present);
-    _mav_put_uint8_t(buf, 85, ethernet_status);
+    _mav_put_float(buf, 68, payload_rx_rssi);
+    _mav_put_float(buf, 72, battery_voltage);
+    _mav_put_uint16_t(buf, 76, main_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 78, main_tx_bitrate);
+    _mav_put_uint16_t(buf, 80, main_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 82, main_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 84, main_rx_bitrate);
+    _mav_put_uint16_t(buf, 86, payload_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 88, payload_tx_bitrate);
+    _mav_put_uint16_t(buf, 90, payload_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 92, payload_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 94, payload_rx_bitrate);
+    _mav_put_uint8_t(buf, 96, gps_fix);
+    _mav_put_uint8_t(buf, 97, main_radio_present);
+    _mav_put_uint8_t(buf, 98, payload_radio_present);
+    _mav_put_uint8_t(buf, 99, ethernet_present);
+    _mav_put_uint8_t(buf, 100, ethernet_status);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN);
 #else
@@ -195,14 +230,21 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
     packet.gps_longitude = gps_longitude;
     packet.gps_height = gps_height;
     packet.main_rx_rssi = main_rx_rssi;
+    packet.payload_rx_rssi = payload_rx_rssi;
     packet.battery_voltage = battery_voltage;
     packet.main_packet_tx_error_count = main_packet_tx_error_count;
     packet.main_tx_bitrate = main_tx_bitrate;
     packet.main_packet_rx_success_count = main_packet_rx_success_count;
     packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
     packet.main_rx_bitrate = main_rx_bitrate;
+    packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
+    packet.payload_tx_bitrate = payload_tx_bitrate;
+    packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
+    packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
+    packet.payload_rx_bitrate = payload_rx_bitrate;
     packet.gps_fix = gps_fix;
     packet.main_radio_present = main_radio_present;
+    packet.payload_radio_present = payload_radio_present;
     packet.ethernet_present = ethernet_present;
     packet.ethernet_status = ethernet_status;
 
@@ -242,6 +284,13 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
  * @param main_packet_rx_drop_count  Number of dropped mavlink packets
  * @param main_rx_bitrate [b/s] Receive bitrate
  * @param main_rx_rssi [dBm] Receive RSSI
+ * @param payload_radio_present  Boolean indicating the presence of the payload radio
+ * @param payload_packet_tx_error_count  Number of errors during send
+ * @param payload_tx_bitrate [b/s] Send bitrate
+ * @param payload_packet_rx_success_count  Number of succesfull received mavlink packets
+ * @param payload_packet_rx_drop_count  Number of dropped mavlink packets
+ * @param payload_rx_bitrate [b/s] Receive bitrate
+ * @param payload_rx_rssi [dBm] Receive RSSI
  * @param ethernet_present  Boolean indicating the presence of the ethernet module
  * @param ethernet_status  Status flag indicating the status of the ethernet PHY
  * @param battery_voltage [V] Battery voltage
@@ -249,7 +298,7 @@ static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t compon
  */
 static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,float yaw,float pitch,float roll,float target_yaw,float target_pitch,float stepperX_pos,float stepperX_delta,float stepperX_speed,float stepperY_pos,float stepperY_delta,float stepperY_speed,float gps_latitude,float gps_longitude,float gps_height,uint8_t gps_fix,uint8_t main_radio_present,uint16_t main_packet_tx_error_count,uint16_t main_tx_bitrate,uint16_t main_packet_rx_success_count,uint16_t main_packet_rx_drop_count,uint16_t main_rx_bitrate,float main_rx_rssi,uint8_t ethernet_present,uint8_t ethernet_status,float battery_voltage)
+                                   uint64_t timestamp,float yaw,float pitch,float roll,float target_yaw,float target_pitch,float stepperX_pos,float stepperX_delta,float stepperX_speed,float stepperY_pos,float stepperY_delta,float stepperY_speed,float gps_latitude,float gps_longitude,float gps_height,uint8_t gps_fix,uint8_t main_radio_present,uint16_t main_packet_tx_error_count,uint16_t main_tx_bitrate,uint16_t main_packet_rx_success_count,uint16_t main_packet_rx_drop_count,uint16_t main_rx_bitrate,float main_rx_rssi,uint8_t payload_radio_present,uint16_t payload_packet_tx_error_count,uint16_t payload_tx_bitrate,uint16_t payload_packet_rx_success_count,uint16_t payload_packet_rx_drop_count,uint16_t payload_rx_bitrate,float payload_rx_rssi,uint8_t ethernet_present,uint8_t ethernet_status,float battery_voltage)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
@@ -269,16 +318,23 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c
     _mav_put_float(buf, 56, gps_longitude);
     _mav_put_float(buf, 60, gps_height);
     _mav_put_float(buf, 64, main_rx_rssi);
-    _mav_put_float(buf, 68, battery_voltage);
-    _mav_put_uint16_t(buf, 72, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 74, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 76, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 78, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 80, main_rx_bitrate);
-    _mav_put_uint8_t(buf, 82, gps_fix);
-    _mav_put_uint8_t(buf, 83, main_radio_present);
-    _mav_put_uint8_t(buf, 84, ethernet_present);
-    _mav_put_uint8_t(buf, 85, ethernet_status);
+    _mav_put_float(buf, 68, payload_rx_rssi);
+    _mav_put_float(buf, 72, battery_voltage);
+    _mav_put_uint16_t(buf, 76, main_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 78, main_tx_bitrate);
+    _mav_put_uint16_t(buf, 80, main_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 82, main_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 84, main_rx_bitrate);
+    _mav_put_uint16_t(buf, 86, payload_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 88, payload_tx_bitrate);
+    _mav_put_uint16_t(buf, 90, payload_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 92, payload_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 94, payload_rx_bitrate);
+    _mav_put_uint8_t(buf, 96, gps_fix);
+    _mav_put_uint8_t(buf, 97, main_radio_present);
+    _mav_put_uint8_t(buf, 98, payload_radio_present);
+    _mav_put_uint8_t(buf, 99, ethernet_present);
+    _mav_put_uint8_t(buf, 100, ethernet_status);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN);
 #else
@@ -299,14 +355,21 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c
     packet.gps_longitude = gps_longitude;
     packet.gps_height = gps_height;
     packet.main_rx_rssi = main_rx_rssi;
+    packet.payload_rx_rssi = payload_rx_rssi;
     packet.battery_voltage = battery_voltage;
     packet.main_packet_tx_error_count = main_packet_tx_error_count;
     packet.main_tx_bitrate = main_tx_bitrate;
     packet.main_packet_rx_success_count = main_packet_rx_success_count;
     packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
     packet.main_rx_bitrate = main_rx_bitrate;
+    packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
+    packet.payload_tx_bitrate = payload_tx_bitrate;
+    packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
+    packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
+    packet.payload_rx_bitrate = payload_rx_bitrate;
     packet.gps_fix = gps_fix;
     packet.main_radio_present = main_radio_present;
+    packet.payload_radio_present = payload_radio_present;
     packet.ethernet_present = ethernet_present;
     packet.ethernet_status = ethernet_status;
 
@@ -327,7 +390,7 @@ static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t c
  */
 static inline uint16_t mavlink_msg_arp_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_arp_tm_t* arp_tm)
 {
-    return mavlink_msg_arp_tm_pack(system_id, component_id, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage);
+    return mavlink_msg_arp_tm_pack(system_id, component_id, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->payload_radio_present, arp_tm->payload_packet_tx_error_count, arp_tm->payload_tx_bitrate, arp_tm->payload_packet_rx_success_count, arp_tm->payload_packet_rx_drop_count, arp_tm->payload_rx_bitrate, arp_tm->payload_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage);
 }
 
 /**
@@ -341,7 +404,7 @@ static inline uint16_t mavlink_msg_arp_tm_encode(uint8_t system_id, uint8_t comp
  */
 static inline uint16_t mavlink_msg_arp_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_arp_tm_t* arp_tm)
 {
-    return mavlink_msg_arp_tm_pack_chan(system_id, component_id, chan, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage);
+    return mavlink_msg_arp_tm_pack_chan(system_id, component_id, chan, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->payload_radio_present, arp_tm->payload_packet_tx_error_count, arp_tm->payload_tx_bitrate, arp_tm->payload_packet_rx_success_count, arp_tm->payload_packet_rx_drop_count, arp_tm->payload_rx_bitrate, arp_tm->payload_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage);
 }
 
 /**
@@ -371,13 +434,20 @@ static inline uint16_t mavlink_msg_arp_tm_encode_chan(uint8_t system_id, uint8_t
  * @param main_packet_rx_drop_count  Number of dropped mavlink packets
  * @param main_rx_bitrate [b/s] Receive bitrate
  * @param main_rx_rssi [dBm] Receive RSSI
+ * @param payload_radio_present  Boolean indicating the presence of the payload radio
+ * @param payload_packet_tx_error_count  Number of errors during send
+ * @param payload_tx_bitrate [b/s] Send bitrate
+ * @param payload_packet_rx_success_count  Number of succesfull received mavlink packets
+ * @param payload_packet_rx_drop_count  Number of dropped mavlink packets
+ * @param payload_rx_bitrate [b/s] Receive bitrate
+ * @param payload_rx_rssi [dBm] Receive RSSI
  * @param ethernet_present  Boolean indicating the presence of the ethernet module
  * @param ethernet_status  Status flag indicating the status of the ethernet PHY
  * @param battery_voltage [V] Battery voltage
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
+static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
@@ -397,16 +467,23 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time
     _mav_put_float(buf, 56, gps_longitude);
     _mav_put_float(buf, 60, gps_height);
     _mav_put_float(buf, 64, main_rx_rssi);
-    _mav_put_float(buf, 68, battery_voltage);
-    _mav_put_uint16_t(buf, 72, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 74, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 76, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 78, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 80, main_rx_bitrate);
-    _mav_put_uint8_t(buf, 82, gps_fix);
-    _mav_put_uint8_t(buf, 83, main_radio_present);
-    _mav_put_uint8_t(buf, 84, ethernet_present);
-    _mav_put_uint8_t(buf, 85, ethernet_status);
+    _mav_put_float(buf, 68, payload_rx_rssi);
+    _mav_put_float(buf, 72, battery_voltage);
+    _mav_put_uint16_t(buf, 76, main_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 78, main_tx_bitrate);
+    _mav_put_uint16_t(buf, 80, main_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 82, main_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 84, main_rx_bitrate);
+    _mav_put_uint16_t(buf, 86, payload_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 88, payload_tx_bitrate);
+    _mav_put_uint16_t(buf, 90, payload_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 92, payload_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 94, payload_rx_bitrate);
+    _mav_put_uint8_t(buf, 96, gps_fix);
+    _mav_put_uint8_t(buf, 97, main_radio_present);
+    _mav_put_uint8_t(buf, 98, payload_radio_present);
+    _mav_put_uint8_t(buf, 99, ethernet_present);
+    _mav_put_uint8_t(buf, 100, ethernet_status);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, buf, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
 #else
@@ -427,14 +504,21 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time
     packet.gps_longitude = gps_longitude;
     packet.gps_height = gps_height;
     packet.main_rx_rssi = main_rx_rssi;
+    packet.payload_rx_rssi = payload_rx_rssi;
     packet.battery_voltage = battery_voltage;
     packet.main_packet_tx_error_count = main_packet_tx_error_count;
     packet.main_tx_bitrate = main_tx_bitrate;
     packet.main_packet_rx_success_count = main_packet_rx_success_count;
     packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
     packet.main_rx_bitrate = main_rx_bitrate;
+    packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
+    packet.payload_tx_bitrate = payload_tx_bitrate;
+    packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
+    packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
+    packet.payload_rx_bitrate = payload_rx_bitrate;
     packet.gps_fix = gps_fix;
     packet.main_radio_present = main_radio_present;
+    packet.payload_radio_present = payload_radio_present;
     packet.ethernet_present = ethernet_present;
     packet.ethernet_status = ethernet_status;
 
@@ -450,7 +534,7 @@ static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t time
 static inline void mavlink_msg_arp_tm_send_struct(mavlink_channel_t chan, const mavlink_arp_tm_t* arp_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_arp_tm_send(chan, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage);
+    mavlink_msg_arp_tm_send(chan, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->payload_radio_present, arp_tm->payload_packet_tx_error_count, arp_tm->payload_tx_bitrate, arp_tm->payload_packet_rx_success_count, arp_tm->payload_packet_rx_drop_count, arp_tm->payload_rx_bitrate, arp_tm->payload_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, (const char *)arp_tm, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
 #endif
@@ -464,7 +548,7 @@ static inline void mavlink_msg_arp_tm_send_struct(mavlink_channel_t chan, const
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
+static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -484,16 +568,23 @@ static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     _mav_put_float(buf, 56, gps_longitude);
     _mav_put_float(buf, 60, gps_height);
     _mav_put_float(buf, 64, main_rx_rssi);
-    _mav_put_float(buf, 68, battery_voltage);
-    _mav_put_uint16_t(buf, 72, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 74, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 76, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 78, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 80, main_rx_bitrate);
-    _mav_put_uint8_t(buf, 82, gps_fix);
-    _mav_put_uint8_t(buf, 83, main_radio_present);
-    _mav_put_uint8_t(buf, 84, ethernet_present);
-    _mav_put_uint8_t(buf, 85, ethernet_status);
+    _mav_put_float(buf, 68, payload_rx_rssi);
+    _mav_put_float(buf, 72, battery_voltage);
+    _mav_put_uint16_t(buf, 76, main_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 78, main_tx_bitrate);
+    _mav_put_uint16_t(buf, 80, main_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 82, main_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 84, main_rx_bitrate);
+    _mav_put_uint16_t(buf, 86, payload_packet_tx_error_count);
+    _mav_put_uint16_t(buf, 88, payload_tx_bitrate);
+    _mav_put_uint16_t(buf, 90, payload_packet_rx_success_count);
+    _mav_put_uint16_t(buf, 92, payload_packet_rx_drop_count);
+    _mav_put_uint16_t(buf, 94, payload_rx_bitrate);
+    _mav_put_uint8_t(buf, 96, gps_fix);
+    _mav_put_uint8_t(buf, 97, main_radio_present);
+    _mav_put_uint8_t(buf, 98, payload_radio_present);
+    _mav_put_uint8_t(buf, 99, ethernet_present);
+    _mav_put_uint8_t(buf, 100, ethernet_status);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, buf, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
 #else
@@ -514,14 +605,21 @@ static inline void mavlink_msg_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     packet->gps_longitude = gps_longitude;
     packet->gps_height = gps_height;
     packet->main_rx_rssi = main_rx_rssi;
+    packet->payload_rx_rssi = payload_rx_rssi;
     packet->battery_voltage = battery_voltage;
     packet->main_packet_tx_error_count = main_packet_tx_error_count;
     packet->main_tx_bitrate = main_tx_bitrate;
     packet->main_packet_rx_success_count = main_packet_rx_success_count;
     packet->main_packet_rx_drop_count = main_packet_rx_drop_count;
     packet->main_rx_bitrate = main_rx_bitrate;
+    packet->payload_packet_tx_error_count = payload_packet_tx_error_count;
+    packet->payload_tx_bitrate = payload_tx_bitrate;
+    packet->payload_packet_rx_success_count = payload_packet_rx_success_count;
+    packet->payload_packet_rx_drop_count = payload_packet_rx_drop_count;
+    packet->payload_rx_bitrate = payload_rx_bitrate;
     packet->gps_fix = gps_fix;
     packet->main_radio_present = main_radio_present;
+    packet->payload_radio_present = payload_radio_present;
     packet->ethernet_present = ethernet_present;
     packet->ethernet_status = ethernet_status;
 
@@ -692,7 +790,7 @@ static inline float mavlink_msg_arp_tm_get_gps_height(const mavlink_message_t* m
  */
 static inline uint8_t mavlink_msg_arp_tm_get_gps_fix(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  82);
+    return _MAV_RETURN_uint8_t(msg,  96);
 }
 
 /**
@@ -702,7 +800,7 @@ static inline uint8_t mavlink_msg_arp_tm_get_gps_fix(const mavlink_message_t* ms
  */
 static inline uint8_t mavlink_msg_arp_tm_get_main_radio_present(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  83);
+    return _MAV_RETURN_uint8_t(msg,  97);
 }
 
 /**
@@ -712,7 +810,7 @@ static inline uint8_t mavlink_msg_arp_tm_get_main_radio_present(const mavlink_me
  */
 static inline uint16_t mavlink_msg_arp_tm_get_main_packet_tx_error_count(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  72);
+    return _MAV_RETURN_uint16_t(msg,  76);
 }
 
 /**
@@ -722,7 +820,7 @@ static inline uint16_t mavlink_msg_arp_tm_get_main_packet_tx_error_count(const m
  */
 static inline uint16_t mavlink_msg_arp_tm_get_main_tx_bitrate(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  74);
+    return _MAV_RETURN_uint16_t(msg,  78);
 }
 
 /**
@@ -732,7 +830,7 @@ static inline uint16_t mavlink_msg_arp_tm_get_main_tx_bitrate(const mavlink_mess
  */
 static inline uint16_t mavlink_msg_arp_tm_get_main_packet_rx_success_count(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  76);
+    return _MAV_RETURN_uint16_t(msg,  80);
 }
 
 /**
@@ -742,7 +840,7 @@ static inline uint16_t mavlink_msg_arp_tm_get_main_packet_rx_success_count(const
  */
 static inline uint16_t mavlink_msg_arp_tm_get_main_packet_rx_drop_count(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  78);
+    return _MAV_RETURN_uint16_t(msg,  82);
 }
 
 /**
@@ -752,7 +850,7 @@ static inline uint16_t mavlink_msg_arp_tm_get_main_packet_rx_drop_count(const ma
  */
 static inline uint16_t mavlink_msg_arp_tm_get_main_rx_bitrate(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  80);
+    return _MAV_RETURN_uint16_t(msg,  84);
 }
 
 /**
@@ -765,6 +863,76 @@ static inline float mavlink_msg_arp_tm_get_main_rx_rssi(const mavlink_message_t*
     return _MAV_RETURN_float(msg,  64);
 }
 
+/**
+ * @brief Get field payload_radio_present from arp_tm message
+ *
+ * @return  Boolean indicating the presence of the payload radio
+ */
+static inline uint8_t mavlink_msg_arp_tm_get_payload_radio_present(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  98);
+}
+
+/**
+ * @brief Get field payload_packet_tx_error_count from arp_tm message
+ *
+ * @return  Number of errors during send
+ */
+static inline uint16_t mavlink_msg_arp_tm_get_payload_packet_tx_error_count(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  86);
+}
+
+/**
+ * @brief Get field payload_tx_bitrate from arp_tm message
+ *
+ * @return [b/s] Send bitrate
+ */
+static inline uint16_t mavlink_msg_arp_tm_get_payload_tx_bitrate(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  88);
+}
+
+/**
+ * @brief Get field payload_packet_rx_success_count from arp_tm message
+ *
+ * @return  Number of succesfull received mavlink packets
+ */
+static inline uint16_t mavlink_msg_arp_tm_get_payload_packet_rx_success_count(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  90);
+}
+
+/**
+ * @brief Get field payload_packet_rx_drop_count from arp_tm message
+ *
+ * @return  Number of dropped mavlink packets
+ */
+static inline uint16_t mavlink_msg_arp_tm_get_payload_packet_rx_drop_count(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  92);
+}
+
+/**
+ * @brief Get field payload_rx_bitrate from arp_tm message
+ *
+ * @return [b/s] Receive bitrate
+ */
+static inline uint16_t mavlink_msg_arp_tm_get_payload_rx_bitrate(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  94);
+}
+
+/**
+ * @brief Get field payload_rx_rssi from arp_tm message
+ *
+ * @return [dBm] Receive RSSI
+ */
+static inline float mavlink_msg_arp_tm_get_payload_rx_rssi(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  68);
+}
+
 /**
  * @brief Get field ethernet_present from arp_tm message
  *
@@ -772,7 +940,7 @@ static inline float mavlink_msg_arp_tm_get_main_rx_rssi(const mavlink_message_t*
  */
 static inline uint8_t mavlink_msg_arp_tm_get_ethernet_present(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  84);
+    return _MAV_RETURN_uint8_t(msg,  99);
 }
 
 /**
@@ -782,7 +950,7 @@ static inline uint8_t mavlink_msg_arp_tm_get_ethernet_present(const mavlink_mess
  */
 static inline uint8_t mavlink_msg_arp_tm_get_ethernet_status(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  85);
+    return _MAV_RETURN_uint8_t(msg,  100);
 }
 
 /**
@@ -792,7 +960,7 @@ static inline uint8_t mavlink_msg_arp_tm_get_ethernet_status(const mavlink_messa
  */
 static inline float mavlink_msg_arp_tm_get_battery_voltage(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  68);
+    return _MAV_RETURN_float(msg,  72);
 }
 
 /**
@@ -820,14 +988,21 @@ static inline void mavlink_msg_arp_tm_decode(const mavlink_message_t* msg, mavli
     arp_tm->gps_longitude = mavlink_msg_arp_tm_get_gps_longitude(msg);
     arp_tm->gps_height = mavlink_msg_arp_tm_get_gps_height(msg);
     arp_tm->main_rx_rssi = mavlink_msg_arp_tm_get_main_rx_rssi(msg);
+    arp_tm->payload_rx_rssi = mavlink_msg_arp_tm_get_payload_rx_rssi(msg);
     arp_tm->battery_voltage = mavlink_msg_arp_tm_get_battery_voltage(msg);
     arp_tm->main_packet_tx_error_count = mavlink_msg_arp_tm_get_main_packet_tx_error_count(msg);
     arp_tm->main_tx_bitrate = mavlink_msg_arp_tm_get_main_tx_bitrate(msg);
     arp_tm->main_packet_rx_success_count = mavlink_msg_arp_tm_get_main_packet_rx_success_count(msg);
     arp_tm->main_packet_rx_drop_count = mavlink_msg_arp_tm_get_main_packet_rx_drop_count(msg);
     arp_tm->main_rx_bitrate = mavlink_msg_arp_tm_get_main_rx_bitrate(msg);
+    arp_tm->payload_packet_tx_error_count = mavlink_msg_arp_tm_get_payload_packet_tx_error_count(msg);
+    arp_tm->payload_tx_bitrate = mavlink_msg_arp_tm_get_payload_tx_bitrate(msg);
+    arp_tm->payload_packet_rx_success_count = mavlink_msg_arp_tm_get_payload_packet_rx_success_count(msg);
+    arp_tm->payload_packet_rx_drop_count = mavlink_msg_arp_tm_get_payload_packet_rx_drop_count(msg);
+    arp_tm->payload_rx_bitrate = mavlink_msg_arp_tm_get_payload_rx_bitrate(msg);
     arp_tm->gps_fix = mavlink_msg_arp_tm_get_gps_fix(msg);
     arp_tm->main_radio_present = mavlink_msg_arp_tm_get_main_radio_present(msg);
+    arp_tm->payload_radio_present = mavlink_msg_arp_tm_get_payload_radio_present(msg);
     arp_tm->ethernet_present = mavlink_msg_arp_tm_get_ethernet_present(msg);
     arp_tm->ethernet_status = mavlink_msg_arp_tm_get_ethernet_status(msg);
 #else
diff --git a/mavlink_lib/lyra/mavlink_msg_attitude_tm.h b/mavlink_lib/lyra/mavlink_msg_attitude_tm.h
index c16dba2fd216b82c35caba889893c630eb261145..0a681388622819c22db57c0aa6e4fa55f9dc5d84 100644
--- a/mavlink_lib/lyra/mavlink_msg_attitude_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_attitude_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE ATTITUDE_TM PACKING
 
-#define MAVLINK_MSG_ID_ATTITUDE_TM 110
+#define MAVLINK_MSG_ID_ATTITUDE_TM 111
 
 
 typedef struct __mavlink_attitude_tm_t {
@@ -18,17 +18,17 @@ typedef struct __mavlink_attitude_tm_t {
 
 #define MAVLINK_MSG_ID_ATTITUDE_TM_LEN 56
 #define MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN 56
-#define MAVLINK_MSG_ID_110_LEN 56
-#define MAVLINK_MSG_ID_110_MIN_LEN 56
+#define MAVLINK_MSG_ID_111_LEN 56
+#define MAVLINK_MSG_ID_111_MIN_LEN 56
 
 #define MAVLINK_MSG_ID_ATTITUDE_TM_CRC 6
-#define MAVLINK_MSG_ID_110_CRC 6
+#define MAVLINK_MSG_ID_111_CRC 6
 
 #define MAVLINK_MSG_ATTITUDE_TM_FIELD_SENSOR_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_ATTITUDE_TM { \
-    110, \
+    111, \
     "ATTITUDE_TM", \
     9, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_can_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_can_stats_tm.h
new file mode 100644
index 0000000000000000000000000000000000000000..4bc1ec272ef1ed3729b762021d2ccbacbc2c1681
--- /dev/null
+++ b/mavlink_lib/lyra/mavlink_msg_can_stats_tm.h
@@ -0,0 +1,288 @@
+#pragma once
+// MESSAGE CAN_STATS_TM PACKING
+
+#define MAVLINK_MSG_ID_CAN_STATS_TM 203
+
+
+typedef struct __mavlink_can_stats_tm_t {
+ uint64_t timestamp; /*< [us] When was this logged*/
+ float payload_bit_rate; /*<  Payload only bitrate*/
+ float total_bit_rate; /*<  Total bitrate*/
+ float load_percent; /*<  Load percent of the BUS*/
+} mavlink_can_stats_tm_t;
+
+#define MAVLINK_MSG_ID_CAN_STATS_TM_LEN 20
+#define MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN 20
+#define MAVLINK_MSG_ID_203_LEN 20
+#define MAVLINK_MSG_ID_203_MIN_LEN 20
+
+#define MAVLINK_MSG_ID_CAN_STATS_TM_CRC 39
+#define MAVLINK_MSG_ID_203_CRC 39
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_CAN_STATS_TM { \
+    203, \
+    "CAN_STATS_TM", \
+    4, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_can_stats_tm_t, timestamp) }, \
+         { "payload_bit_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_can_stats_tm_t, payload_bit_rate) }, \
+         { "total_bit_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_can_stats_tm_t, total_bit_rate) }, \
+         { "load_percent", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_can_stats_tm_t, load_percent) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_CAN_STATS_TM { \
+    "CAN_STATS_TM", \
+    4, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_can_stats_tm_t, timestamp) }, \
+         { "payload_bit_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_can_stats_tm_t, payload_bit_rate) }, \
+         { "total_bit_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_can_stats_tm_t, total_bit_rate) }, \
+         { "load_percent", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_can_stats_tm_t, load_percent) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a can_stats_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] When was this logged
+ * @param payload_bit_rate  Payload only bitrate
+ * @param total_bit_rate  Total bitrate
+ * @param load_percent  Load percent of the BUS
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_can_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint64_t timestamp, float payload_bit_rate, float total_bit_rate, float load_percent)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_CAN_STATS_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, payload_bit_rate);
+    _mav_put_float(buf, 12, total_bit_rate);
+    _mav_put_float(buf, 16, load_percent);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAN_STATS_TM_LEN);
+#else
+    mavlink_can_stats_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.payload_bit_rate = payload_bit_rate;
+    packet.total_bit_rate = total_bit_rate;
+    packet.load_percent = load_percent;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAN_STATS_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_CAN_STATS_TM;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_CRC);
+}
+
+/**
+ * @brief Pack a can_stats_tm message 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 payload_bit_rate  Payload only bitrate
+ * @param total_bit_rate  Total bitrate
+ * @param load_percent  Load percent of the BUS
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_can_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint64_t timestamp,float payload_bit_rate,float total_bit_rate,float load_percent)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_CAN_STATS_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, payload_bit_rate);
+    _mav_put_float(buf, 12, total_bit_rate);
+    _mav_put_float(buf, 16, load_percent);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAN_STATS_TM_LEN);
+#else
+    mavlink_can_stats_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.payload_bit_rate = payload_bit_rate;
+    packet.total_bit_rate = total_bit_rate;
+    packet.load_percent = load_percent;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAN_STATS_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_CAN_STATS_TM;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_CRC);
+}
+
+/**
+ * @brief Encode a can_stats_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 can_stats_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_can_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_can_stats_tm_t* can_stats_tm)
+{
+    return mavlink_msg_can_stats_tm_pack(system_id, component_id, msg, can_stats_tm->timestamp, can_stats_tm->payload_bit_rate, can_stats_tm->total_bit_rate, can_stats_tm->load_percent);
+}
+
+/**
+ * @brief Encode a can_stats_tm struct 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 can_stats_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_can_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_can_stats_tm_t* can_stats_tm)
+{
+    return mavlink_msg_can_stats_tm_pack_chan(system_id, component_id, chan, msg, can_stats_tm->timestamp, can_stats_tm->payload_bit_rate, can_stats_tm->total_bit_rate, can_stats_tm->load_percent);
+}
+
+/**
+ * @brief Send a can_stats_tm message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param timestamp [us] When was this logged
+ * @param payload_bit_rate  Payload only bitrate
+ * @param total_bit_rate  Total bitrate
+ * @param load_percent  Load percent of the BUS
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_can_stats_tm_send(mavlink_channel_t chan, uint64_t timestamp, float payload_bit_rate, float total_bit_rate, float load_percent)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_CAN_STATS_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, payload_bit_rate);
+    _mav_put_float(buf, 12, total_bit_rate);
+    _mav_put_float(buf, 16, load_percent);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_STATS_TM, buf, MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_CRC);
+#else
+    mavlink_can_stats_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.payload_bit_rate = payload_bit_rate;
+    packet.total_bit_rate = total_bit_rate;
+    packet.load_percent = load_percent;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_CRC);
+#endif
+}
+
+/**
+ * @brief Send a can_stats_tm message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_can_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_can_stats_tm_t* can_stats_tm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_can_stats_tm_send(chan, can_stats_tm->timestamp, can_stats_tm->payload_bit_rate, can_stats_tm->total_bit_rate, can_stats_tm->load_percent);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_STATS_TM, (const char *)can_stats_tm, MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_CAN_STATS_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_can_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float payload_bit_rate, float total_bit_rate, float load_percent)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, payload_bit_rate);
+    _mav_put_float(buf, 12, total_bit_rate);
+    _mav_put_float(buf, 16, load_percent);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_STATS_TM, buf, MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_CRC);
+#else
+    mavlink_can_stats_tm_t *packet = (mavlink_can_stats_tm_t *)msgbuf;
+    packet->timestamp = timestamp;
+    packet->payload_bit_rate = payload_bit_rate;
+    packet->total_bit_rate = total_bit_rate;
+    packet->load_percent = load_percent;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_LEN, MAVLINK_MSG_ID_CAN_STATS_TM_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE CAN_STATS_TM UNPACKING
+
+
+/**
+ * @brief Get field timestamp from can_stats_tm message
+ *
+ * @return [us] When was this logged
+ */
+static inline uint64_t mavlink_msg_can_stats_tm_get_timestamp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint64_t(msg,  0);
+}
+
+/**
+ * @brief Get field payload_bit_rate from can_stats_tm message
+ *
+ * @return  Payload only bitrate
+ */
+static inline float mavlink_msg_can_stats_tm_get_payload_bit_rate(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  8);
+}
+
+/**
+ * @brief Get field total_bit_rate from can_stats_tm message
+ *
+ * @return  Total bitrate
+ */
+static inline float mavlink_msg_can_stats_tm_get_total_bit_rate(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  12);
+}
+
+/**
+ * @brief Get field load_percent from can_stats_tm message
+ *
+ * @return  Load percent of the BUS
+ */
+static inline float mavlink_msg_can_stats_tm_get_load_percent(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  16);
+}
+
+/**
+ * @brief Decode a can_stats_tm message into a struct
+ *
+ * @param msg The message to decode
+ * @param can_stats_tm C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_can_stats_tm_decode(const mavlink_message_t* msg, mavlink_can_stats_tm_t* can_stats_tm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    can_stats_tm->timestamp = mavlink_msg_can_stats_tm_get_timestamp(msg);
+    can_stats_tm->payload_bit_rate = mavlink_msg_can_stats_tm_get_payload_bit_rate(msg);
+    can_stats_tm->total_bit_rate = mavlink_msg_can_stats_tm_get_total_bit_rate(msg);
+    can_stats_tm->load_percent = mavlink_msg_can_stats_tm_get_load_percent(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_CAN_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_CAN_STATS_TM_LEN;
+        memset(can_stats_tm, 0, MAVLINK_MSG_ID_CAN_STATS_TM_LEN);
+    memcpy(can_stats_tm, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/mavlink_lib/lyra/mavlink_msg_conrig_state_tc.h b/mavlink_lib/lyra/mavlink_msg_conrig_state_tc.h
index 9f1ada850a2a7f233ba5f5e9ae41e55121488da2..c3da8f3c2bca3b8ea850a40a3307f1f50db67626 100644
--- a/mavlink_lib/lyra/mavlink_msg_conrig_state_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_conrig_state_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE CONRIG_STATE_TC PACKING
 
-#define MAVLINK_MSG_ID_CONRIG_STATE_TC 19
+#define MAVLINK_MSG_ID_CONRIG_STATE_TC 32
 
 
 typedef struct __mavlink_conrig_state_tc_t {
@@ -16,17 +16,17 @@ typedef struct __mavlink_conrig_state_tc_t {
 
 #define MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN 7
 #define MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN 7
-#define MAVLINK_MSG_ID_19_LEN 7
-#define MAVLINK_MSG_ID_19_MIN_LEN 7
+#define MAVLINK_MSG_ID_32_LEN 7
+#define MAVLINK_MSG_ID_32_MIN_LEN 7
 
 #define MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC 65
-#define MAVLINK_MSG_ID_19_CRC 65
+#define MAVLINK_MSG_ID_32_CRC 65
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC { \
-    19, \
+    32, \
     "CONRIG_STATE_TC", \
     7, \
     {  { "ignition_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_conrig_state_tc_t, ignition_btn) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_current_tm.h b/mavlink_lib/lyra/mavlink_msg_current_tm.h
index a63460b470e330fb90ada85f4cf61a1ec67401b2..47206857c5d71f9e52ac94532df8bb6660f40792 100644
--- a/mavlink_lib/lyra/mavlink_msg_current_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_current_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE CURRENT_TM PACKING
 
-#define MAVLINK_MSG_ID_CURRENT_TM 107
+#define MAVLINK_MSG_ID_CURRENT_TM 108
 
 
 typedef struct __mavlink_current_tm_t {
@@ -12,17 +12,17 @@ typedef struct __mavlink_current_tm_t {
 
 #define MAVLINK_MSG_ID_CURRENT_TM_LEN 32
 #define MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_107_LEN 32
-#define MAVLINK_MSG_ID_107_MIN_LEN 32
+#define MAVLINK_MSG_ID_108_LEN 32
+#define MAVLINK_MSG_ID_108_MIN_LEN 32
 
 #define MAVLINK_MSG_ID_CURRENT_TM_CRC 212
-#define MAVLINK_MSG_ID_107_CRC 212
+#define MAVLINK_MSG_ID_108_CRC 212
 
 #define MAVLINK_MSG_CURRENT_TM_FIELD_SENSOR_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_CURRENT_TM { \
-    107, \
+    108, \
     "CURRENT_TM", \
     3, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_current_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_fsm_tm.h b/mavlink_lib/lyra/mavlink_msg_fsm_tm.h
deleted file mode 100644
index cc60afc359614defcc489ad0497c01e43dfc908a..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_fsm_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE FSM_TM PACKING
-
-#define MAVLINK_MSG_ID_FSM_TM 201
-
-
-typedef struct __mavlink_fsm_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- uint8_t ada_state; /*<  Apogee Detection Algorithm state*/
- uint8_t abk_state; /*<  Air Brakes state*/
- uint8_t dpl_state; /*<  Deployment state*/
- uint8_t fmm_state; /*<  Flight Mode Manager state*/
- uint8_t nas_state; /*<  Navigation and Attitude System state*/
- uint8_t wes_state; /*<  Wind Estimation System state*/
-} mavlink_fsm_tm_t;
-
-#define MAVLINK_MSG_ID_FSM_TM_LEN 14
-#define MAVLINK_MSG_ID_FSM_TM_MIN_LEN 14
-#define MAVLINK_MSG_ID_201_LEN 14
-#define MAVLINK_MSG_ID_201_MIN_LEN 14
-
-#define MAVLINK_MSG_ID_FSM_TM_CRC 242
-#define MAVLINK_MSG_ID_201_CRC 242
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_FSM_TM { \
-    201, \
-    "FSM_TM", \
-    7, \
-    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fsm_tm_t, timestamp) }, \
-         { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fsm_tm_t, ada_state) }, \
-         { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fsm_tm_t, abk_state) }, \
-         { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fsm_tm_t, dpl_state) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fsm_tm_t, fmm_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_fsm_tm_t, nas_state) }, \
-         { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_fsm_tm_t, wes_state) }, \
-         } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_FSM_TM { \
-    "FSM_TM", \
-    7, \
-    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fsm_tm_t, timestamp) }, \
-         { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fsm_tm_t, ada_state) }, \
-         { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fsm_tm_t, abk_state) }, \
-         { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fsm_tm_t, dpl_state) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fsm_tm_t, fmm_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_fsm_tm_t, nas_state) }, \
-         { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_fsm_tm_t, wes_state) }, \
-         } \
-}
-#endif
-
-/**
- * @brief Pack a fsm_tm message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- *
- * @param timestamp [us] Timestamp
- * @param ada_state  Apogee Detection Algorithm state
- * @param abk_state  Air Brakes state
- * @param dpl_state  Deployment state
- * @param fmm_state  Flight Mode Manager state
- * @param nas_state  Navigation and Attitude System state
- * @param wes_state  Wind Estimation System state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_fsm_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
-    _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_uint8_t(buf, 8, ada_state);
-    _mav_put_uint8_t(buf, 9, abk_state);
-    _mav_put_uint8_t(buf, 10, dpl_state);
-    _mav_put_uint8_t(buf, 11, fmm_state);
-    _mav_put_uint8_t(buf, 12, nas_state);
-    _mav_put_uint8_t(buf, 13, wes_state);
-
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FSM_TM_LEN);
-#else
-    mavlink_fsm_tm_t packet;
-    packet.timestamp = timestamp;
-    packet.ada_state = ada_state;
-    packet.abk_state = abk_state;
-    packet.dpl_state = dpl_state;
-    packet.fmm_state = fmm_state;
-    packet.nas_state = nas_state;
-    packet.wes_state = wes_state;
-
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FSM_TM_LEN);
-#endif
-
-    msg->msgid = MAVLINK_MSG_ID_FSM_TM;
-    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-}
-
-/**
- * @brief Pack a fsm_tm message on a channel
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message will be sent over
- * @param msg The MAVLink message to compress the data into
- * @param timestamp [us] Timestamp
- * @param ada_state  Apogee Detection Algorithm state
- * @param abk_state  Air Brakes state
- * @param dpl_state  Deployment state
- * @param fmm_state  Flight Mode Manager state
- * @param nas_state  Navigation and Attitude System state
- * @param wes_state  Wind Estimation System state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_fsm_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 abk_state,uint8_t dpl_state,uint8_t fmm_state,uint8_t nas_state,uint8_t wes_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
-    _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_uint8_t(buf, 8, ada_state);
-    _mav_put_uint8_t(buf, 9, abk_state);
-    _mav_put_uint8_t(buf, 10, dpl_state);
-    _mav_put_uint8_t(buf, 11, fmm_state);
-    _mav_put_uint8_t(buf, 12, nas_state);
-    _mav_put_uint8_t(buf, 13, wes_state);
-
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FSM_TM_LEN);
-#else
-    mavlink_fsm_tm_t packet;
-    packet.timestamp = timestamp;
-    packet.ada_state = ada_state;
-    packet.abk_state = abk_state;
-    packet.dpl_state = dpl_state;
-    packet.fmm_state = fmm_state;
-    packet.nas_state = nas_state;
-    packet.wes_state = wes_state;
-
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FSM_TM_LEN);
-#endif
-
-    msg->msgid = MAVLINK_MSG_ID_FSM_TM;
-    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-}
-
-/**
- * @brief Encode a fsm_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 fsm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_fsm_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fsm_tm_t* fsm_tm)
-{
-    return mavlink_msg_fsm_tm_pack(system_id, component_id, msg, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state, fsm_tm->wes_state);
-}
-
-/**
- * @brief Encode a fsm_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 fsm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_fsm_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fsm_tm_t* fsm_tm)
-{
-    return mavlink_msg_fsm_tm_pack_chan(system_id, component_id, chan, msg, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state, fsm_tm->wes_state);
-}
-
-/**
- * @brief Send a fsm_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param ada_state  Apogee Detection Algorithm state
- * @param abk_state  Air Brakes state
- * @param dpl_state  Deployment state
- * @param fmm_state  Flight Mode Manager state
- * @param nas_state  Navigation and Attitude System state
- * @param wes_state  Wind Estimation System state
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_fsm_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
-    _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_uint8_t(buf, 8, ada_state);
-    _mav_put_uint8_t(buf, 9, abk_state);
-    _mav_put_uint8_t(buf, 10, dpl_state);
-    _mav_put_uint8_t(buf, 11, fmm_state);
-    _mav_put_uint8_t(buf, 12, nas_state);
-    _mav_put_uint8_t(buf, 13, wes_state);
-
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, buf, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#else
-    mavlink_fsm_tm_t packet;
-    packet.timestamp = timestamp;
-    packet.ada_state = ada_state;
-    packet.abk_state = abk_state;
-    packet.dpl_state = dpl_state;
-    packet.fmm_state = fmm_state;
-    packet.nas_state = nas_state;
-    packet.wes_state = wes_state;
-
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)&packet, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a fsm_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_fsm_tm_send_struct(mavlink_channel_t chan, const mavlink_fsm_tm_t* fsm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_fsm_tm_send(chan, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state, fsm_tm->wes_state);
-#else
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)fsm_tm, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_FSM_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_fsm_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char *buf = (char *)msgbuf;
-    _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_uint8_t(buf, 8, ada_state);
-    _mav_put_uint8_t(buf, 9, abk_state);
-    _mav_put_uint8_t(buf, 10, dpl_state);
-    _mav_put_uint8_t(buf, 11, fmm_state);
-    _mav_put_uint8_t(buf, 12, nas_state);
-    _mav_put_uint8_t(buf, 13, wes_state);
-
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, buf, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#else
-    mavlink_fsm_tm_t *packet = (mavlink_fsm_tm_t *)msgbuf;
-    packet->timestamp = timestamp;
-    packet->ada_state = ada_state;
-    packet->abk_state = abk_state;
-    packet->dpl_state = dpl_state;
-    packet->fmm_state = fmm_state;
-    packet->nas_state = nas_state;
-    packet->wes_state = wes_state;
-
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)packet, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE FSM_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from fsm_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_fsm_tm_get_timestamp(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint64_t(msg,  0);
-}
-
-/**
- * @brief Get field ada_state from fsm_tm message
- *
- * @return  Apogee Detection Algorithm state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_ada_state(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  8);
-}
-
-/**
- * @brief Get field abk_state from fsm_tm message
- *
- * @return  Air Brakes state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_abk_state(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  9);
-}
-
-/**
- * @brief Get field dpl_state from fsm_tm message
- *
- * @return  Deployment state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_dpl_state(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  10);
-}
-
-/**
- * @brief Get field fmm_state from fsm_tm message
- *
- * @return  Flight Mode Manager state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_fmm_state(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  11);
-}
-
-/**
- * @brief Get field nas_state from fsm_tm message
- *
- * @return  Navigation and Attitude System state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_nas_state(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  12);
-}
-
-/**
- * @brief Get field wes_state from fsm_tm message
- *
- * @return  Wind Estimation System state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_wes_state(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  13);
-}
-
-/**
- * @brief Decode a fsm_tm message into a struct
- *
- * @param msg The message to decode
- * @param fsm_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_fsm_tm_decode(const mavlink_message_t* msg, mavlink_fsm_tm_t* fsm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    fsm_tm->timestamp = mavlink_msg_fsm_tm_get_timestamp(msg);
-    fsm_tm->ada_state = mavlink_msg_fsm_tm_get_ada_state(msg);
-    fsm_tm->abk_state = mavlink_msg_fsm_tm_get_abk_state(msg);
-    fsm_tm->dpl_state = mavlink_msg_fsm_tm_get_dpl_state(msg);
-    fsm_tm->fmm_state = mavlink_msg_fsm_tm_get_fmm_state(msg);
-    fsm_tm->nas_state = mavlink_msg_fsm_tm_get_nas_state(msg);
-    fsm_tm->wes_state = mavlink_msg_fsm_tm_get_wes_state(msg);
-#else
-        uint8_t len = msg->len < MAVLINK_MSG_ID_FSM_TM_LEN? msg->len : MAVLINK_MSG_ID_FSM_TM_LEN;
-        memset(fsm_tm, 0, MAVLINK_MSG_ID_FSM_TM_LEN);
-    memcpy(fsm_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_gps_tm.h b/mavlink_lib/lyra/mavlink_msg_gps_tm.h
index 96f4891e5530a812d22ae2891cded1543bfddd74..d2fd3a488c044808074b29d10d0fb95f0fc92118 100644
--- a/mavlink_lib/lyra/mavlink_msg_gps_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_gps_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE GPS_TM PACKING
 
-#define MAVLINK_MSG_ID_GPS_TM 102
+#define MAVLINK_MSG_ID_GPS_TM 103
 
 
 typedef struct __mavlink_gps_tm_t {
@@ -21,17 +21,17 @@ typedef struct __mavlink_gps_tm_t {
 
 #define MAVLINK_MSG_ID_GPS_TM_LEN 74
 #define MAVLINK_MSG_ID_GPS_TM_MIN_LEN 74
-#define MAVLINK_MSG_ID_102_LEN 74
-#define MAVLINK_MSG_ID_102_MIN_LEN 74
+#define MAVLINK_MSG_ID_103_LEN 74
+#define MAVLINK_MSG_ID_103_MIN_LEN 74
 
 #define MAVLINK_MSG_ID_GPS_TM_CRC 57
-#define MAVLINK_MSG_ID_102_CRC 57
+#define MAVLINK_MSG_ID_103_CRC 57
 
 #define MAVLINK_MSG_GPS_TM_FIELD_SENSOR_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_GPS_TM { \
-    102, \
+    103, \
     "GPS_TM", \
     12, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_gse_tm.h b/mavlink_lib/lyra/mavlink_msg_gse_tm.h
index 2719d6a99924abb8ac4fabe2b3a9b54e187d80b8..a2b898320cced664284c0022f94c49b071147cb6 100644
--- a/mavlink_lib/lyra/mavlink_msg_gse_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_gse_tm.h
@@ -11,27 +11,33 @@ typedef struct __mavlink_gse_tm_t {
  float filling_pressure; /*< [Bar] Refueling line pressure*/
  float vessel_pressure; /*< [Bar] Vessel tank pressure*/
  float battery_voltage; /*<  Battery voltage*/
- float current_consumption; /*<   RIG current */
- uint8_t arming_state; /*<  1 If the rocket is armed*/
+ float current_consumption; /*< [A] RIG current*/
+ float umbilical_current_consumption; /*< [A] Umbilical current*/
+ int32_t log_good; /*<  0 if log failed, 1 otherwise*/
+ int16_t log_number; /*<  Currently active log file, -1 if the logger is inactive*/
  uint8_t filling_valve_state; /*<  1 If the filling valve is open*/
  uint8_t venting_valve_state; /*<  1 If the venting valve is open*/
  uint8_t release_valve_state; /*<  1 If the release valve is open*/
  uint8_t main_valve_state; /*<  1 If the main valve is open*/
  uint8_t nitrogen_valve_state; /*<   1 If the nitrogen valve is open*/
  uint8_t gmm_state; /*<  State of the GroundModeManager*/
- uint8_t tars_state; /*<  1 If the TARS algorithm is running*/
- uint8_t main_board_status; /*<   MAIN board status [0: not present, 1: online, 2: armed]*/
- uint8_t payload_board_status; /*<   PAYLOAD board status [0: not present, 1: online, 2: armed]*/
- uint8_t motor_board_status; /*<   MOTOR board status [0: not present, 1: online, 2: armed]*/
+ uint8_t tars_state; /*<  State of Tars*/
+ uint8_t arming_state; /*<  Arming state (1 if armed, 0 otherwise)*/
+ uint8_t main_board_state; /*<  Main board fmm state*/
+ uint8_t payload_board_state; /*<  Payload board fmm state*/
+ uint8_t motor_board_state; /*<  Motor board fmm state*/
+ uint8_t main_can_status; /*<  Main CAN status*/
+ uint8_t payload_can_status; /*<  Payload CAN status*/
+ uint8_t motor_can_status; /*<  Motor CAN status*/
 } mavlink_gse_tm_t;
 
-#define MAVLINK_MSG_ID_GSE_TM_LEN 43
-#define MAVLINK_MSG_ID_GSE_TM_MIN_LEN 43
-#define MAVLINK_MSG_ID_212_LEN 43
-#define MAVLINK_MSG_ID_212_MIN_LEN 43
+#define MAVLINK_MSG_ID_GSE_TM_LEN 56
+#define MAVLINK_MSG_ID_GSE_TM_MIN_LEN 56
+#define MAVLINK_MSG_ID_212_LEN 56
+#define MAVLINK_MSG_ID_212_MIN_LEN 56
 
-#define MAVLINK_MSG_ID_GSE_TM_CRC 81
-#define MAVLINK_MSG_ID_212_CRC 81
+#define MAVLINK_MSG_ID_GSE_TM_CRC 33
+#define MAVLINK_MSG_ID_212_CRC 33
 
 
 
@@ -39,49 +45,61 @@ typedef struct __mavlink_gse_tm_t {
 #define MAVLINK_MESSAGE_INFO_GSE_TM { \
     212, \
     "GSE_TM", \
-    18, \
+    24, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gse_tm_t, timestamp) }, \
          { "loadcell_rocket", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gse_tm_t, loadcell_rocket) }, \
          { "loadcell_vessel", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gse_tm_t, loadcell_vessel) }, \
          { "filling_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gse_tm_t, filling_pressure) }, \
          { "vessel_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gse_tm_t, vessel_pressure) }, \
-         { "arming_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gse_tm_t, arming_state) }, \
-         { "filling_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gse_tm_t, filling_valve_state) }, \
-         { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gse_tm_t, venting_valve_state) }, \
-         { "release_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_gse_tm_t, release_valve_state) }, \
-         { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_gse_tm_t, main_valve_state) }, \
-         { "nitrogen_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_gse_tm_t, nitrogen_valve_state) }, \
-         { "gmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_gse_tm_t, gmm_state) }, \
-         { "tars_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_gse_tm_t, tars_state) }, \
+         { "filling_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_gse_tm_t, filling_valve_state) }, \
+         { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_gse_tm_t, venting_valve_state) }, \
+         { "release_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_gse_tm_t, release_valve_state) }, \
+         { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_gse_tm_t, main_valve_state) }, \
+         { "nitrogen_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 46, offsetof(mavlink_gse_tm_t, nitrogen_valve_state) }, \
+         { "gmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 47, offsetof(mavlink_gse_tm_t, gmm_state) }, \
+         { "tars_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_gse_tm_t, tars_state) }, \
+         { "arming_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_gse_tm_t, arming_state) }, \
          { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gse_tm_t, battery_voltage) }, \
          { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gse_tm_t, current_consumption) }, \
-         { "main_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_gse_tm_t, main_board_status) }, \
-         { "payload_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_gse_tm_t, payload_board_status) }, \
-         { "motor_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_gse_tm_t, motor_board_status) }, \
+         { "umbilical_current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gse_tm_t, umbilical_current_consumption) }, \
+         { "main_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_gse_tm_t, main_board_state) }, \
+         { "payload_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_gse_tm_t, payload_board_state) }, \
+         { "motor_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_gse_tm_t, motor_board_state) }, \
+         { "main_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_gse_tm_t, main_can_status) }, \
+         { "payload_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 54, offsetof(mavlink_gse_tm_t, payload_can_status) }, \
+         { "motor_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 55, offsetof(mavlink_gse_tm_t, motor_can_status) }, \
+         { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_gse_tm_t, log_number) }, \
+         { "log_good", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_gse_tm_t, log_good) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_GSE_TM { \
     "GSE_TM", \
-    18, \
+    24, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gse_tm_t, timestamp) }, \
          { "loadcell_rocket", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gse_tm_t, loadcell_rocket) }, \
          { "loadcell_vessel", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gse_tm_t, loadcell_vessel) }, \
          { "filling_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gse_tm_t, filling_pressure) }, \
          { "vessel_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gse_tm_t, vessel_pressure) }, \
-         { "arming_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gse_tm_t, arming_state) }, \
-         { "filling_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gse_tm_t, filling_valve_state) }, \
-         { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gse_tm_t, venting_valve_state) }, \
-         { "release_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_gse_tm_t, release_valve_state) }, \
-         { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_gse_tm_t, main_valve_state) }, \
-         { "nitrogen_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_gse_tm_t, nitrogen_valve_state) }, \
-         { "gmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_gse_tm_t, gmm_state) }, \
-         { "tars_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_gse_tm_t, tars_state) }, \
+         { "filling_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_gse_tm_t, filling_valve_state) }, \
+         { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_gse_tm_t, venting_valve_state) }, \
+         { "release_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_gse_tm_t, release_valve_state) }, \
+         { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_gse_tm_t, main_valve_state) }, \
+         { "nitrogen_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 46, offsetof(mavlink_gse_tm_t, nitrogen_valve_state) }, \
+         { "gmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 47, offsetof(mavlink_gse_tm_t, gmm_state) }, \
+         { "tars_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_gse_tm_t, tars_state) }, \
+         { "arming_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_gse_tm_t, arming_state) }, \
          { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gse_tm_t, battery_voltage) }, \
          { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gse_tm_t, current_consumption) }, \
-         { "main_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_gse_tm_t, main_board_status) }, \
-         { "payload_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_gse_tm_t, payload_board_status) }, \
-         { "motor_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_gse_tm_t, motor_board_status) }, \
+         { "umbilical_current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gse_tm_t, umbilical_current_consumption) }, \
+         { "main_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_gse_tm_t, main_board_state) }, \
+         { "payload_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_gse_tm_t, payload_board_state) }, \
+         { "motor_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_gse_tm_t, motor_board_state) }, \
+         { "main_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_gse_tm_t, main_can_status) }, \
+         { "payload_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 54, offsetof(mavlink_gse_tm_t, payload_can_status) }, \
+         { "motor_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 55, offsetof(mavlink_gse_tm_t, motor_can_status) }, \
+         { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_gse_tm_t, log_number) }, \
+         { "log_good", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_gse_tm_t, log_good) }, \
          } \
 }
 #endif
@@ -97,23 +115,29 @@ typedef struct __mavlink_gse_tm_t {
  * @param loadcell_vessel [kg] External tank weight
  * @param filling_pressure [Bar] Refueling line pressure
  * @param vessel_pressure [Bar] Vessel tank pressure
- * @param arming_state  1 If the rocket is armed
  * @param filling_valve_state  1 If the filling valve is open
  * @param venting_valve_state  1 If the venting valve is open
  * @param release_valve_state  1 If the release valve is open
  * @param main_valve_state  1 If the main valve is open
  * @param nitrogen_valve_state   1 If the nitrogen valve is open
  * @param gmm_state  State of the GroundModeManager
- * @param tars_state  1 If the TARS algorithm is running
+ * @param tars_state  State of Tars
+ * @param arming_state  Arming state (1 if armed, 0 otherwise)
  * @param battery_voltage  Battery voltage
- * @param current_consumption   RIG current 
- * @param main_board_status   MAIN board status [0: not present, 1: online, 2: armed]
- * @param payload_board_status   PAYLOAD board status [0: not present, 1: online, 2: armed]
- * @param motor_board_status   MOTOR board status [0: not present, 1: online, 2: armed]
+ * @param current_consumption [A] RIG current
+ * @param umbilical_current_consumption [A] Umbilical current
+ * @param main_board_state  Main board fmm state
+ * @param payload_board_state  Payload board fmm state
+ * @param motor_board_state  Motor board fmm state
+ * @param main_can_status  Main CAN status
+ * @param payload_can_status  Payload CAN status
+ * @param motor_can_status  Motor CAN status
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param log_good  0 if log failed, 1 otherwise
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t gmm_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
+                               uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t gmm_state, uint8_t tars_state, uint8_t arming_state, float battery_voltage, float current_consumption, float umbilical_current_consumption, uint8_t main_board_state, uint8_t payload_board_state, uint8_t motor_board_state, uint8_t main_can_status, uint8_t payload_can_status, uint8_t motor_can_status, int16_t log_number, int32_t log_good)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
@@ -124,17 +148,23 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon
     _mav_put_float(buf, 20, vessel_pressure);
     _mav_put_float(buf, 24, battery_voltage);
     _mav_put_float(buf, 28, current_consumption);
-    _mav_put_uint8_t(buf, 32, arming_state);
-    _mav_put_uint8_t(buf, 33, filling_valve_state);
-    _mav_put_uint8_t(buf, 34, venting_valve_state);
-    _mav_put_uint8_t(buf, 35, release_valve_state);
-    _mav_put_uint8_t(buf, 36, main_valve_state);
-    _mav_put_uint8_t(buf, 37, nitrogen_valve_state);
-    _mav_put_uint8_t(buf, 38, gmm_state);
-    _mav_put_uint8_t(buf, 39, tars_state);
-    _mav_put_uint8_t(buf, 40, main_board_status);
-    _mav_put_uint8_t(buf, 41, payload_board_status);
-    _mav_put_uint8_t(buf, 42, motor_board_status);
+    _mav_put_float(buf, 32, umbilical_current_consumption);
+    _mav_put_int32_t(buf, 36, log_good);
+    _mav_put_int16_t(buf, 40, log_number);
+    _mav_put_uint8_t(buf, 42, filling_valve_state);
+    _mav_put_uint8_t(buf, 43, venting_valve_state);
+    _mav_put_uint8_t(buf, 44, release_valve_state);
+    _mav_put_uint8_t(buf, 45, main_valve_state);
+    _mav_put_uint8_t(buf, 46, nitrogen_valve_state);
+    _mav_put_uint8_t(buf, 47, gmm_state);
+    _mav_put_uint8_t(buf, 48, tars_state);
+    _mav_put_uint8_t(buf, 49, arming_state);
+    _mav_put_uint8_t(buf, 50, main_board_state);
+    _mav_put_uint8_t(buf, 51, payload_board_state);
+    _mav_put_uint8_t(buf, 52, motor_board_state);
+    _mav_put_uint8_t(buf, 53, main_can_status);
+    _mav_put_uint8_t(buf, 54, payload_can_status);
+    _mav_put_uint8_t(buf, 55, motor_can_status);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GSE_TM_LEN);
 #else
@@ -146,7 +176,9 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon
     packet.vessel_pressure = vessel_pressure;
     packet.battery_voltage = battery_voltage;
     packet.current_consumption = current_consumption;
-    packet.arming_state = arming_state;
+    packet.umbilical_current_consumption = umbilical_current_consumption;
+    packet.log_good = log_good;
+    packet.log_number = log_number;
     packet.filling_valve_state = filling_valve_state;
     packet.venting_valve_state = venting_valve_state;
     packet.release_valve_state = release_valve_state;
@@ -154,9 +186,13 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon
     packet.nitrogen_valve_state = nitrogen_valve_state;
     packet.gmm_state = gmm_state;
     packet.tars_state = tars_state;
-    packet.main_board_status = main_board_status;
-    packet.payload_board_status = payload_board_status;
-    packet.motor_board_status = motor_board_status;
+    packet.arming_state = arming_state;
+    packet.main_board_state = main_board_state;
+    packet.payload_board_state = payload_board_state;
+    packet.motor_board_state = motor_board_state;
+    packet.main_can_status = main_can_status;
+    packet.payload_can_status = payload_can_status;
+    packet.motor_can_status = motor_can_status;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GSE_TM_LEN);
 #endif
@@ -176,24 +212,30 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon
  * @param loadcell_vessel [kg] External tank weight
  * @param filling_pressure [Bar] Refueling line pressure
  * @param vessel_pressure [Bar] Vessel tank pressure
- * @param arming_state  1 If the rocket is armed
  * @param filling_valve_state  1 If the filling valve is open
  * @param venting_valve_state  1 If the venting valve is open
  * @param release_valve_state  1 If the release valve is open
  * @param main_valve_state  1 If the main valve is open
  * @param nitrogen_valve_state   1 If the nitrogen valve is open
  * @param gmm_state  State of the GroundModeManager
- * @param tars_state  1 If the TARS algorithm is running
+ * @param tars_state  State of Tars
+ * @param arming_state  Arming state (1 if armed, 0 otherwise)
  * @param battery_voltage  Battery voltage
- * @param current_consumption   RIG current 
- * @param main_board_status   MAIN board status [0: not present, 1: online, 2: armed]
- * @param payload_board_status   PAYLOAD board status [0: not present, 1: online, 2: armed]
- * @param motor_board_status   MOTOR board status [0: not present, 1: online, 2: armed]
+ * @param current_consumption [A] RIG current
+ * @param umbilical_current_consumption [A] Umbilical current
+ * @param main_board_state  Main board fmm state
+ * @param payload_board_state  Payload board fmm state
+ * @param motor_board_state  Motor board fmm state
+ * @param main_can_status  Main CAN status
+ * @param payload_can_status  Payload CAN status
+ * @param motor_can_status  Motor CAN status
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param log_good  0 if log failed, 1 otherwise
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,float loadcell_rocket,float loadcell_vessel,float filling_pressure,float vessel_pressure,uint8_t arming_state,uint8_t filling_valve_state,uint8_t venting_valve_state,uint8_t release_valve_state,uint8_t main_valve_state,uint8_t nitrogen_valve_state,uint8_t gmm_state,uint8_t tars_state,float battery_voltage,float current_consumption,uint8_t main_board_status,uint8_t payload_board_status,uint8_t motor_board_status)
+                                   uint64_t timestamp,float loadcell_rocket,float loadcell_vessel,float filling_pressure,float vessel_pressure,uint8_t filling_valve_state,uint8_t venting_valve_state,uint8_t release_valve_state,uint8_t main_valve_state,uint8_t nitrogen_valve_state,uint8_t gmm_state,uint8_t tars_state,uint8_t arming_state,float battery_voltage,float current_consumption,float umbilical_current_consumption,uint8_t main_board_state,uint8_t payload_board_state,uint8_t motor_board_state,uint8_t main_can_status,uint8_t payload_can_status,uint8_t motor_can_status,int16_t log_number,int32_t log_good)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
@@ -204,17 +246,23 @@ static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t c
     _mav_put_float(buf, 20, vessel_pressure);
     _mav_put_float(buf, 24, battery_voltage);
     _mav_put_float(buf, 28, current_consumption);
-    _mav_put_uint8_t(buf, 32, arming_state);
-    _mav_put_uint8_t(buf, 33, filling_valve_state);
-    _mav_put_uint8_t(buf, 34, venting_valve_state);
-    _mav_put_uint8_t(buf, 35, release_valve_state);
-    _mav_put_uint8_t(buf, 36, main_valve_state);
-    _mav_put_uint8_t(buf, 37, nitrogen_valve_state);
-    _mav_put_uint8_t(buf, 38, gmm_state);
-    _mav_put_uint8_t(buf, 39, tars_state);
-    _mav_put_uint8_t(buf, 40, main_board_status);
-    _mav_put_uint8_t(buf, 41, payload_board_status);
-    _mav_put_uint8_t(buf, 42, motor_board_status);
+    _mav_put_float(buf, 32, umbilical_current_consumption);
+    _mav_put_int32_t(buf, 36, log_good);
+    _mav_put_int16_t(buf, 40, log_number);
+    _mav_put_uint8_t(buf, 42, filling_valve_state);
+    _mav_put_uint8_t(buf, 43, venting_valve_state);
+    _mav_put_uint8_t(buf, 44, release_valve_state);
+    _mav_put_uint8_t(buf, 45, main_valve_state);
+    _mav_put_uint8_t(buf, 46, nitrogen_valve_state);
+    _mav_put_uint8_t(buf, 47, gmm_state);
+    _mav_put_uint8_t(buf, 48, tars_state);
+    _mav_put_uint8_t(buf, 49, arming_state);
+    _mav_put_uint8_t(buf, 50, main_board_state);
+    _mav_put_uint8_t(buf, 51, payload_board_state);
+    _mav_put_uint8_t(buf, 52, motor_board_state);
+    _mav_put_uint8_t(buf, 53, main_can_status);
+    _mav_put_uint8_t(buf, 54, payload_can_status);
+    _mav_put_uint8_t(buf, 55, motor_can_status);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GSE_TM_LEN);
 #else
@@ -226,7 +274,9 @@ static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t c
     packet.vessel_pressure = vessel_pressure;
     packet.battery_voltage = battery_voltage;
     packet.current_consumption = current_consumption;
-    packet.arming_state = arming_state;
+    packet.umbilical_current_consumption = umbilical_current_consumption;
+    packet.log_good = log_good;
+    packet.log_number = log_number;
     packet.filling_valve_state = filling_valve_state;
     packet.venting_valve_state = venting_valve_state;
     packet.release_valve_state = release_valve_state;
@@ -234,9 +284,13 @@ static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t c
     packet.nitrogen_valve_state = nitrogen_valve_state;
     packet.gmm_state = gmm_state;
     packet.tars_state = tars_state;
-    packet.main_board_status = main_board_status;
-    packet.payload_board_status = payload_board_status;
-    packet.motor_board_status = motor_board_status;
+    packet.arming_state = arming_state;
+    packet.main_board_state = main_board_state;
+    packet.payload_board_state = payload_board_state;
+    packet.motor_board_state = motor_board_state;
+    packet.main_can_status = main_can_status;
+    packet.payload_can_status = payload_can_status;
+    packet.motor_can_status = motor_can_status;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GSE_TM_LEN);
 #endif
@@ -255,7 +309,7 @@ static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t c
  */
 static inline uint16_t mavlink_msg_gse_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gse_tm_t* gse_tm)
 {
-    return mavlink_msg_gse_tm_pack(system_id, component_id, msg, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->gmm_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
+    return mavlink_msg_gse_tm_pack(system_id, component_id, msg, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->gmm_state, gse_tm->tars_state, gse_tm->arming_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->umbilical_current_consumption, gse_tm->main_board_state, gse_tm->payload_board_state, gse_tm->motor_board_state, gse_tm->main_can_status, gse_tm->payload_can_status, gse_tm->motor_can_status, gse_tm->log_number, gse_tm->log_good);
 }
 
 /**
@@ -269,7 +323,7 @@ static inline uint16_t mavlink_msg_gse_tm_encode(uint8_t system_id, uint8_t comp
  */
 static inline uint16_t mavlink_msg_gse_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gse_tm_t* gse_tm)
 {
-    return mavlink_msg_gse_tm_pack_chan(system_id, component_id, chan, msg, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->gmm_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
+    return mavlink_msg_gse_tm_pack_chan(system_id, component_id, chan, msg, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->gmm_state, gse_tm->tars_state, gse_tm->arming_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->umbilical_current_consumption, gse_tm->main_board_state, gse_tm->payload_board_state, gse_tm->motor_board_state, gse_tm->main_can_status, gse_tm->payload_can_status, gse_tm->motor_can_status, gse_tm->log_number, gse_tm->log_good);
 }
 
 /**
@@ -281,23 +335,29 @@ static inline uint16_t mavlink_msg_gse_tm_encode_chan(uint8_t system_id, uint8_t
  * @param loadcell_vessel [kg] External tank weight
  * @param filling_pressure [Bar] Refueling line pressure
  * @param vessel_pressure [Bar] Vessel tank pressure
- * @param arming_state  1 If the rocket is armed
  * @param filling_valve_state  1 If the filling valve is open
  * @param venting_valve_state  1 If the venting valve is open
  * @param release_valve_state  1 If the release valve is open
  * @param main_valve_state  1 If the main valve is open
  * @param nitrogen_valve_state   1 If the nitrogen valve is open
  * @param gmm_state  State of the GroundModeManager
- * @param tars_state  1 If the TARS algorithm is running
+ * @param tars_state  State of Tars
+ * @param arming_state  Arming state (1 if armed, 0 otherwise)
  * @param battery_voltage  Battery voltage
- * @param current_consumption   RIG current 
- * @param main_board_status   MAIN board status [0: not present, 1: online, 2: armed]
- * @param payload_board_status   PAYLOAD board status [0: not present, 1: online, 2: armed]
- * @param motor_board_status   MOTOR board status [0: not present, 1: online, 2: armed]
+ * @param current_consumption [A] RIG current
+ * @param umbilical_current_consumption [A] Umbilical current
+ * @param main_board_state  Main board fmm state
+ * @param payload_board_state  Payload board fmm state
+ * @param motor_board_state  Motor board fmm state
+ * @param main_can_status  Main CAN status
+ * @param payload_can_status  Payload CAN status
+ * @param motor_can_status  Motor CAN status
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param log_good  0 if log failed, 1 otherwise
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t gmm_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
+static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t gmm_state, uint8_t tars_state, uint8_t arming_state, float battery_voltage, float current_consumption, float umbilical_current_consumption, uint8_t main_board_state, uint8_t payload_board_state, uint8_t motor_board_state, uint8_t main_can_status, uint8_t payload_can_status, uint8_t motor_can_status, int16_t log_number, int32_t log_good)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
@@ -308,17 +368,23 @@ static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t time
     _mav_put_float(buf, 20, vessel_pressure);
     _mav_put_float(buf, 24, battery_voltage);
     _mav_put_float(buf, 28, current_consumption);
-    _mav_put_uint8_t(buf, 32, arming_state);
-    _mav_put_uint8_t(buf, 33, filling_valve_state);
-    _mav_put_uint8_t(buf, 34, venting_valve_state);
-    _mav_put_uint8_t(buf, 35, release_valve_state);
-    _mav_put_uint8_t(buf, 36, main_valve_state);
-    _mav_put_uint8_t(buf, 37, nitrogen_valve_state);
-    _mav_put_uint8_t(buf, 38, gmm_state);
-    _mav_put_uint8_t(buf, 39, tars_state);
-    _mav_put_uint8_t(buf, 40, main_board_status);
-    _mav_put_uint8_t(buf, 41, payload_board_status);
-    _mav_put_uint8_t(buf, 42, motor_board_status);
+    _mav_put_float(buf, 32, umbilical_current_consumption);
+    _mav_put_int32_t(buf, 36, log_good);
+    _mav_put_int16_t(buf, 40, log_number);
+    _mav_put_uint8_t(buf, 42, filling_valve_state);
+    _mav_put_uint8_t(buf, 43, venting_valve_state);
+    _mav_put_uint8_t(buf, 44, release_valve_state);
+    _mav_put_uint8_t(buf, 45, main_valve_state);
+    _mav_put_uint8_t(buf, 46, nitrogen_valve_state);
+    _mav_put_uint8_t(buf, 47, gmm_state);
+    _mav_put_uint8_t(buf, 48, tars_state);
+    _mav_put_uint8_t(buf, 49, arming_state);
+    _mav_put_uint8_t(buf, 50, main_board_state);
+    _mav_put_uint8_t(buf, 51, payload_board_state);
+    _mav_put_uint8_t(buf, 52, motor_board_state);
+    _mav_put_uint8_t(buf, 53, main_can_status);
+    _mav_put_uint8_t(buf, 54, payload_can_status);
+    _mav_put_uint8_t(buf, 55, motor_can_status);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, buf, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
 #else
@@ -330,7 +396,9 @@ static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t time
     packet.vessel_pressure = vessel_pressure;
     packet.battery_voltage = battery_voltage;
     packet.current_consumption = current_consumption;
-    packet.arming_state = arming_state;
+    packet.umbilical_current_consumption = umbilical_current_consumption;
+    packet.log_good = log_good;
+    packet.log_number = log_number;
     packet.filling_valve_state = filling_valve_state;
     packet.venting_valve_state = venting_valve_state;
     packet.release_valve_state = release_valve_state;
@@ -338,9 +406,13 @@ static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t time
     packet.nitrogen_valve_state = nitrogen_valve_state;
     packet.gmm_state = gmm_state;
     packet.tars_state = tars_state;
-    packet.main_board_status = main_board_status;
-    packet.payload_board_status = payload_board_status;
-    packet.motor_board_status = motor_board_status;
+    packet.arming_state = arming_state;
+    packet.main_board_state = main_board_state;
+    packet.payload_board_state = payload_board_state;
+    packet.motor_board_state = motor_board_state;
+    packet.main_can_status = main_can_status;
+    packet.payload_can_status = payload_can_status;
+    packet.motor_can_status = motor_can_status;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, (const char *)&packet, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
 #endif
@@ -354,7 +426,7 @@ static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t time
 static inline void mavlink_msg_gse_tm_send_struct(mavlink_channel_t chan, const mavlink_gse_tm_t* gse_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_gse_tm_send(chan, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->gmm_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
+    mavlink_msg_gse_tm_send(chan, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->nitrogen_valve_state, gse_tm->gmm_state, gse_tm->tars_state, gse_tm->arming_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->umbilical_current_consumption, gse_tm->main_board_state, gse_tm->payload_board_state, gse_tm->motor_board_state, gse_tm->main_can_status, gse_tm->payload_can_status, gse_tm->motor_can_status, gse_tm->log_number, gse_tm->log_good);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, (const char *)gse_tm, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
 #endif
@@ -368,7 +440,7 @@ static inline void mavlink_msg_gse_tm_send_struct(mavlink_channel_t chan, const
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t gmm_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
+static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t nitrogen_valve_state, uint8_t gmm_state, uint8_t tars_state, uint8_t arming_state, float battery_voltage, float current_consumption, float umbilical_current_consumption, uint8_t main_board_state, uint8_t payload_board_state, uint8_t motor_board_state, uint8_t main_can_status, uint8_t payload_can_status, uint8_t motor_can_status, int16_t log_number, int32_t log_good)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -379,17 +451,23 @@ static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     _mav_put_float(buf, 20, vessel_pressure);
     _mav_put_float(buf, 24, battery_voltage);
     _mav_put_float(buf, 28, current_consumption);
-    _mav_put_uint8_t(buf, 32, arming_state);
-    _mav_put_uint8_t(buf, 33, filling_valve_state);
-    _mav_put_uint8_t(buf, 34, venting_valve_state);
-    _mav_put_uint8_t(buf, 35, release_valve_state);
-    _mav_put_uint8_t(buf, 36, main_valve_state);
-    _mav_put_uint8_t(buf, 37, nitrogen_valve_state);
-    _mav_put_uint8_t(buf, 38, gmm_state);
-    _mav_put_uint8_t(buf, 39, tars_state);
-    _mav_put_uint8_t(buf, 40, main_board_status);
-    _mav_put_uint8_t(buf, 41, payload_board_status);
-    _mav_put_uint8_t(buf, 42, motor_board_status);
+    _mav_put_float(buf, 32, umbilical_current_consumption);
+    _mav_put_int32_t(buf, 36, log_good);
+    _mav_put_int16_t(buf, 40, log_number);
+    _mav_put_uint8_t(buf, 42, filling_valve_state);
+    _mav_put_uint8_t(buf, 43, venting_valve_state);
+    _mav_put_uint8_t(buf, 44, release_valve_state);
+    _mav_put_uint8_t(buf, 45, main_valve_state);
+    _mav_put_uint8_t(buf, 46, nitrogen_valve_state);
+    _mav_put_uint8_t(buf, 47, gmm_state);
+    _mav_put_uint8_t(buf, 48, tars_state);
+    _mav_put_uint8_t(buf, 49, arming_state);
+    _mav_put_uint8_t(buf, 50, main_board_state);
+    _mav_put_uint8_t(buf, 51, payload_board_state);
+    _mav_put_uint8_t(buf, 52, motor_board_state);
+    _mav_put_uint8_t(buf, 53, main_can_status);
+    _mav_put_uint8_t(buf, 54, payload_can_status);
+    _mav_put_uint8_t(buf, 55, motor_can_status);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, buf, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
 #else
@@ -401,7 +479,9 @@ static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     packet->vessel_pressure = vessel_pressure;
     packet->battery_voltage = battery_voltage;
     packet->current_consumption = current_consumption;
-    packet->arming_state = arming_state;
+    packet->umbilical_current_consumption = umbilical_current_consumption;
+    packet->log_good = log_good;
+    packet->log_number = log_number;
     packet->filling_valve_state = filling_valve_state;
     packet->venting_valve_state = venting_valve_state;
     packet->release_valve_state = release_valve_state;
@@ -409,9 +489,13 @@ static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     packet->nitrogen_valve_state = nitrogen_valve_state;
     packet->gmm_state = gmm_state;
     packet->tars_state = tars_state;
-    packet->main_board_status = main_board_status;
-    packet->payload_board_status = payload_board_status;
-    packet->motor_board_status = motor_board_status;
+    packet->arming_state = arming_state;
+    packet->main_board_state = main_board_state;
+    packet->payload_board_state = payload_board_state;
+    packet->motor_board_state = motor_board_state;
+    packet->main_can_status = main_can_status;
+    packet->payload_can_status = payload_can_status;
+    packet->motor_can_status = motor_can_status;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, (const char *)packet, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
 #endif
@@ -473,16 +557,6 @@ static inline float mavlink_msg_gse_tm_get_vessel_pressure(const mavlink_message
     return _MAV_RETURN_float(msg,  20);
 }
 
-/**
- * @brief Get field arming_state from gse_tm message
- *
- * @return  1 If the rocket is armed
- */
-static inline uint8_t mavlink_msg_gse_tm_get_arming_state(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  32);
-}
-
 /**
  * @brief Get field filling_valve_state from gse_tm message
  *
@@ -490,7 +564,7 @@ static inline uint8_t mavlink_msg_gse_tm_get_arming_state(const mavlink_message_
  */
 static inline uint8_t mavlink_msg_gse_tm_get_filling_valve_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  33);
+    return _MAV_RETURN_uint8_t(msg,  42);
 }
 
 /**
@@ -500,7 +574,7 @@ static inline uint8_t mavlink_msg_gse_tm_get_filling_valve_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_gse_tm_get_venting_valve_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  34);
+    return _MAV_RETURN_uint8_t(msg,  43);
 }
 
 /**
@@ -510,7 +584,7 @@ static inline uint8_t mavlink_msg_gse_tm_get_venting_valve_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_gse_tm_get_release_valve_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  35);
+    return _MAV_RETURN_uint8_t(msg,  44);
 }
 
 /**
@@ -520,7 +594,7 @@ static inline uint8_t mavlink_msg_gse_tm_get_release_valve_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_gse_tm_get_main_valve_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  36);
+    return _MAV_RETURN_uint8_t(msg,  45);
 }
 
 /**
@@ -530,7 +604,7 @@ static inline uint8_t mavlink_msg_gse_tm_get_main_valve_state(const mavlink_mess
  */
 static inline uint8_t mavlink_msg_gse_tm_get_nitrogen_valve_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  37);
+    return _MAV_RETURN_uint8_t(msg,  46);
 }
 
 /**
@@ -540,17 +614,27 @@ static inline uint8_t mavlink_msg_gse_tm_get_nitrogen_valve_state(const mavlink_
  */
 static inline uint8_t mavlink_msg_gse_tm_get_gmm_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  38);
+    return _MAV_RETURN_uint8_t(msg,  47);
 }
 
 /**
  * @brief Get field tars_state from gse_tm message
  *
- * @return  1 If the TARS algorithm is running
+ * @return  State of Tars
  */
 static inline uint8_t mavlink_msg_gse_tm_get_tars_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  39);
+    return _MAV_RETURN_uint8_t(msg,  48);
+}
+
+/**
+ * @brief Get field arming_state from gse_tm message
+ *
+ * @return  Arming state (1 if armed, 0 otherwise)
+ */
+static inline uint8_t mavlink_msg_gse_tm_get_arming_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  49);
 }
 
 /**
@@ -566,7 +650,7 @@ static inline float mavlink_msg_gse_tm_get_battery_voltage(const mavlink_message
 /**
  * @brief Get field current_consumption from gse_tm message
  *
- * @return   RIG current 
+ * @return [A] RIG current
  */
 static inline float mavlink_msg_gse_tm_get_current_consumption(const mavlink_message_t* msg)
 {
@@ -574,33 +658,93 @@ static inline float mavlink_msg_gse_tm_get_current_consumption(const mavlink_mes
 }
 
 /**
- * @brief Get field main_board_status from gse_tm message
+ * @brief Get field umbilical_current_consumption from gse_tm message
  *
- * @return   MAIN board status [0: not present, 1: online, 2: armed]
+ * @return [A] Umbilical current
  */
-static inline uint8_t mavlink_msg_gse_tm_get_main_board_status(const mavlink_message_t* msg)
+static inline float mavlink_msg_gse_tm_get_umbilical_current_consumption(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  40);
+    return _MAV_RETURN_float(msg,  32);
 }
 
 /**
- * @brief Get field payload_board_status from gse_tm message
+ * @brief Get field main_board_state from gse_tm message
  *
- * @return   PAYLOAD board status [0: not present, 1: online, 2: armed]
+ * @return  Main board fmm state
  */
-static inline uint8_t mavlink_msg_gse_tm_get_payload_board_status(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_gse_tm_get_main_board_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  41);
+    return _MAV_RETURN_uint8_t(msg,  50);
 }
 
 /**
- * @brief Get field motor_board_status from gse_tm message
+ * @brief Get field payload_board_state from gse_tm message
  *
- * @return   MOTOR board status [0: not present, 1: online, 2: armed]
+ * @return  Payload board fmm state
  */
-static inline uint8_t mavlink_msg_gse_tm_get_motor_board_status(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_gse_tm_get_payload_board_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  42);
+    return _MAV_RETURN_uint8_t(msg,  51);
+}
+
+/**
+ * @brief Get field motor_board_state from gse_tm message
+ *
+ * @return  Motor board fmm state
+ */
+static inline uint8_t mavlink_msg_gse_tm_get_motor_board_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  52);
+}
+
+/**
+ * @brief Get field main_can_status from gse_tm message
+ *
+ * @return  Main CAN status
+ */
+static inline uint8_t mavlink_msg_gse_tm_get_main_can_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  53);
+}
+
+/**
+ * @brief Get field payload_can_status from gse_tm message
+ *
+ * @return  Payload CAN status
+ */
+static inline uint8_t mavlink_msg_gse_tm_get_payload_can_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  54);
+}
+
+/**
+ * @brief Get field motor_can_status from gse_tm message
+ *
+ * @return  Motor CAN status
+ */
+static inline uint8_t mavlink_msg_gse_tm_get_motor_can_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  55);
+}
+
+/**
+ * @brief Get field log_number from gse_tm message
+ *
+ * @return  Currently active log file, -1 if the logger is inactive
+ */
+static inline int16_t mavlink_msg_gse_tm_get_log_number(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  40);
+}
+
+/**
+ * @brief Get field log_good from gse_tm message
+ *
+ * @return  0 if log failed, 1 otherwise
+ */
+static inline int32_t mavlink_msg_gse_tm_get_log_good(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  36);
 }
 
 /**
@@ -619,7 +763,9 @@ static inline void mavlink_msg_gse_tm_decode(const mavlink_message_t* msg, mavli
     gse_tm->vessel_pressure = mavlink_msg_gse_tm_get_vessel_pressure(msg);
     gse_tm->battery_voltage = mavlink_msg_gse_tm_get_battery_voltage(msg);
     gse_tm->current_consumption = mavlink_msg_gse_tm_get_current_consumption(msg);
-    gse_tm->arming_state = mavlink_msg_gse_tm_get_arming_state(msg);
+    gse_tm->umbilical_current_consumption = mavlink_msg_gse_tm_get_umbilical_current_consumption(msg);
+    gse_tm->log_good = mavlink_msg_gse_tm_get_log_good(msg);
+    gse_tm->log_number = mavlink_msg_gse_tm_get_log_number(msg);
     gse_tm->filling_valve_state = mavlink_msg_gse_tm_get_filling_valve_state(msg);
     gse_tm->venting_valve_state = mavlink_msg_gse_tm_get_venting_valve_state(msg);
     gse_tm->release_valve_state = mavlink_msg_gse_tm_get_release_valve_state(msg);
@@ -627,9 +773,13 @@ static inline void mavlink_msg_gse_tm_decode(const mavlink_message_t* msg, mavli
     gse_tm->nitrogen_valve_state = mavlink_msg_gse_tm_get_nitrogen_valve_state(msg);
     gse_tm->gmm_state = mavlink_msg_gse_tm_get_gmm_state(msg);
     gse_tm->tars_state = mavlink_msg_gse_tm_get_tars_state(msg);
-    gse_tm->main_board_status = mavlink_msg_gse_tm_get_main_board_status(msg);
-    gse_tm->payload_board_status = mavlink_msg_gse_tm_get_payload_board_status(msg);
-    gse_tm->motor_board_status = mavlink_msg_gse_tm_get_motor_board_status(msg);
+    gse_tm->arming_state = mavlink_msg_gse_tm_get_arming_state(msg);
+    gse_tm->main_board_state = mavlink_msg_gse_tm_get_main_board_state(msg);
+    gse_tm->payload_board_state = mavlink_msg_gse_tm_get_payload_board_state(msg);
+    gse_tm->motor_board_state = mavlink_msg_gse_tm_get_motor_board_state(msg);
+    gse_tm->main_can_status = mavlink_msg_gse_tm_get_main_can_status(msg);
+    gse_tm->payload_can_status = mavlink_msg_gse_tm_get_payload_can_status(msg);
+    gse_tm->motor_can_status = mavlink_msg_gse_tm_get_motor_can_status(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_GSE_TM_LEN? msg->len : MAVLINK_MSG_ID_GSE_TM_LEN;
         memset(gse_tm, 0, MAVLINK_MSG_ID_GSE_TM_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_imu_tm.h b/mavlink_lib/lyra/mavlink_msg_imu_tm.h
index 23c4739ce795a498ca8a3df799443719c003547b..1ce0401a5bfdcb2013beeb08914ea6115e1da2cb 100644
--- a/mavlink_lib/lyra/mavlink_msg_imu_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_imu_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE IMU_TM PACKING
 
-#define MAVLINK_MSG_ID_IMU_TM 103
+#define MAVLINK_MSG_ID_IMU_TM 104
 
 
 typedef struct __mavlink_imu_tm_t {
@@ -20,17 +20,17 @@ typedef struct __mavlink_imu_tm_t {
 
 #define MAVLINK_MSG_ID_IMU_TM_LEN 64
 #define MAVLINK_MSG_ID_IMU_TM_MIN_LEN 64
-#define MAVLINK_MSG_ID_103_LEN 64
-#define MAVLINK_MSG_ID_103_MIN_LEN 64
+#define MAVLINK_MSG_ID_104_LEN 64
+#define MAVLINK_MSG_ID_104_MIN_LEN 64
 
 #define MAVLINK_MSG_ID_IMU_TM_CRC 72
-#define MAVLINK_MSG_ID_103_CRC 72
+#define MAVLINK_MSG_ID_104_CRC 72
 
 #define MAVLINK_MSG_IMU_TM_FIELD_SENSOR_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_IMU_TM { \
-    103, \
+    104, \
     "IMU_TM", \
     11, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_imu_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_load_tm.h b/mavlink_lib/lyra/mavlink_msg_load_tm.h
index 27c578f3b208b1174ea5499a1e31a0497c925d07..d93d5e301a3ad5c13003cf6ea37d33329f24ee91 100644
--- a/mavlink_lib/lyra/mavlink_msg_load_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_load_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE LOAD_TM PACKING
 
-#define MAVLINK_MSG_ID_LOAD_TM 109
+#define MAVLINK_MSG_ID_LOAD_TM 110
 
 
 typedef struct __mavlink_load_tm_t {
@@ -12,17 +12,17 @@ typedef struct __mavlink_load_tm_t {
 
 #define MAVLINK_MSG_ID_LOAD_TM_LEN 32
 #define MAVLINK_MSG_ID_LOAD_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_109_LEN 32
-#define MAVLINK_MSG_ID_109_MIN_LEN 32
+#define MAVLINK_MSG_ID_110_LEN 32
+#define MAVLINK_MSG_ID_110_MIN_LEN 32
 
 #define MAVLINK_MSG_ID_LOAD_TM_CRC 148
-#define MAVLINK_MSG_ID_109_CRC 148
+#define MAVLINK_MSG_ID_110_CRC 148
 
 #define MAVLINK_MSG_LOAD_TM_FIELD_SENSOR_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_LOAD_TM { \
-    109, \
+    110, \
     "LOAD_TM", \
     3, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_load_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_logger_tm.h b/mavlink_lib/lyra/mavlink_msg_logger_tm.h
index ac52b5a9d5faa26bb0047de6f0c67293ff6fe4f5..774424b626afd390bab1065fafad81eea390af1c 100644
--- a/mavlink_lib/lyra/mavlink_msg_logger_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_logger_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE LOGGER_TM PACKING
 
-#define MAVLINK_MSG_ID_LOGGER_TM 202
+#define MAVLINK_MSG_ID_LOGGER_TM 201
 
 
 typedef struct __mavlink_logger_tm_t {
@@ -20,17 +20,17 @@ typedef struct __mavlink_logger_tm_t {
 
 #define MAVLINK_MSG_ID_LOGGER_TM_LEN 46
 #define MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN 46
-#define MAVLINK_MSG_ID_202_LEN 46
-#define MAVLINK_MSG_ID_202_MIN_LEN 46
+#define MAVLINK_MSG_ID_201_LEN 46
+#define MAVLINK_MSG_ID_201_MIN_LEN 46
 
 #define MAVLINK_MSG_ID_LOGGER_TM_CRC 142
-#define MAVLINK_MSG_ID_202_CRC 142
+#define MAVLINK_MSG_ID_201_CRC 142
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_LOGGER_TM { \
-    202, \
+    201, \
     "LOGGER_TM", \
     11, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_logger_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_mavlink_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_mavlink_stats_tm.h
index ba89b5f0761bcadff4201e229880cd30f7b90358..70bc63247f7ab08a34c0bcd15cae5d11c7727100 100644
--- a/mavlink_lib/lyra/mavlink_msg_mavlink_stats_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_mavlink_stats_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE MAVLINK_STATS_TM PACKING
 
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM 203
+#define MAVLINK_MSG_ID_MAVLINK_STATS_TM 202
 
 
 typedef struct __mavlink_mavlink_stats_tm_t {
@@ -22,17 +22,17 @@ typedef struct __mavlink_mavlink_stats_tm_t {
 
 #define MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN 28
 #define MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN 28
-#define MAVLINK_MSG_ID_203_LEN 28
-#define MAVLINK_MSG_ID_203_MIN_LEN 28
+#define MAVLINK_MSG_ID_202_LEN 28
+#define MAVLINK_MSG_ID_202_MIN_LEN 28
 
 #define MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC 108
-#define MAVLINK_MSG_ID_203_CRC 108
+#define MAVLINK_MSG_ID_202_CRC 108
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM { \
-    203, \
+    202, \
     "MAVLINK_STATS_TM", \
     13, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mavlink_stats_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_mea_tm.h b/mavlink_lib/lyra/mavlink_msg_mea_tm.h
index a3887d7e6363b14616deca868632f1fc6c0d3b26..dafa6490105c6b3af62244e0c8c1f29b73d00d4b 100644
--- a/mavlink_lib/lyra/mavlink_msg_mea_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_mea_tm.h
@@ -10,7 +10,7 @@ typedef struct __mavlink_mea_tm_t {
  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*/
+ float corrected_pressure; /*< [Pa] Corrected pressure*/
  uint8_t state; /*<  MEA current state*/
 } mavlink_mea_tm_t;
 
@@ -65,7 +65,7 @@ typedef struct __mavlink_mea_tm_t {
  * @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
+ * @param corrected_pressure [Pa] Corrected pressure
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_mea_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -111,7 +111,7 @@ static inline uint16_t mavlink_msg_mea_tm_pack(uint8_t system_id, uint8_t compon
  * @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
+ * @param corrected_pressure [Pa] Corrected pressure
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_mea_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -183,7 +183,7 @@ static inline uint16_t mavlink_msg_mea_tm_encode_chan(uint8_t system_id, uint8_t
  * @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
+ * @param corrected_pressure [Pa] Corrected pressure
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
@@ -332,7 +332,7 @@ static inline float mavlink_msg_mea_tm_get_mass(const mavlink_message_t* msg)
 /**
  * @brief Get field corrected_pressure from mea_tm message
  *
- * @return [kg] Corrected pressure
+ * @return [Pa] Corrected pressure
  */
 static inline float mavlink_msg_mea_tm_get_corrected_pressure(const mavlink_message_t* msg)
 {
diff --git a/mavlink_lib/lyra/mavlink_msg_motor_tm.h b/mavlink_lib/lyra/mavlink_msg_motor_tm.h
index 66102446f17e7a22ab85d5b45231838c7aa10695..42a26a13161d0556257cd6bdd12bfe38a5882460 100644
--- a/mavlink_lib/lyra/mavlink_msg_motor_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_motor_tm.h
@@ -11,18 +11,20 @@ typedef struct __mavlink_motor_tm_t {
  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*/
+ int32_t log_good; /*<  0 if log failed, 1 otherwise*/
+ int16_t log_number; /*<  Currently active log file, -1 if the logger is inactive*/
  uint8_t main_valve_state; /*<  1 If the main valve is open */
  uint8_t venting_valve_state; /*<  1 If the venting valve is open */
+ uint8_t hil_state; /*<  1 if the board is currently in HIL mode*/
 } mavlink_motor_tm_t;
 
-#define MAVLINK_MSG_ID_MOTOR_TM_LEN 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_LEN 37
+#define MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN 37
+#define MAVLINK_MSG_ID_213_LEN 37
+#define MAVLINK_MSG_ID_213_MIN_LEN 37
 
-#define MAVLINK_MSG_ID_MOTOR_TM_CRC 89
-#define MAVLINK_MSG_ID_213_CRC 89
+#define MAVLINK_MSG_ID_MOTOR_TM_CRC 67
+#define MAVLINK_MSG_ID_213_CRC 67
 
 
 
@@ -30,31 +32,35 @@ typedef struct __mavlink_motor_tm_t {
 #define MAVLINK_MESSAGE_INFO_MOTOR_TM { \
     213, \
     "MOTOR_TM", \
-    9, \
+    11, \
     {  { "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) }, \
          { "tank_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_motor_tm_t, tank_temperature) }, \
-         { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_motor_tm_t, main_valve_state) }, \
-         { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_motor_tm_t, venting_valve_state) }, \
+         { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_motor_tm_t, main_valve_state) }, \
+         { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_motor_tm_t, venting_valve_state) }, \
          { "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) }, \
+         { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 32, offsetof(mavlink_motor_tm_t, log_number) }, \
+         { "log_good", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_motor_tm_t, log_good) }, \
+         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_motor_tm_t, hil_state) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_MOTOR_TM { \
     "MOTOR_TM", \
-    9, \
+    11, \
     {  { "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) }, \
          { "tank_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_motor_tm_t, tank_temperature) }, \
-         { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_motor_tm_t, main_valve_state) }, \
-         { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_motor_tm_t, venting_valve_state) }, \
+         { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_motor_tm_t, main_valve_state) }, \
+         { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_motor_tm_t, venting_valve_state) }, \
          { "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) }, \
+         { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 32, offsetof(mavlink_motor_tm_t, log_number) }, \
+         { "log_good", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_motor_tm_t, log_good) }, \
+         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_motor_tm_t, hil_state) }, \
          } \
 }
 #endif
@@ -73,11 +79,13 @@ typedef struct __mavlink_motor_tm_t {
  * @param main_valve_state  1 If the main valve is open 
  * @param venting_valve_state  1 If the venting valve is open 
  * @param battery_voltage [V] Battery voltage
- * @param current_consumption [A] Current drained from the battery
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param log_good  0 if log failed, 1 otherwise
+ * @param hil_state  1 if the board is currently in HIL mode
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, float current_consumption)
+                               uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, int16_t log_number, int32_t log_good, uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
@@ -87,9 +95,11 @@ static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t comp
     _mav_put_float(buf, 16, combustion_chamber_pressure);
     _mav_put_float(buf, 20, tank_temperature);
     _mav_put_float(buf, 24, battery_voltage);
-    _mav_put_float(buf, 28, current_consumption);
-    _mav_put_uint8_t(buf, 32, main_valve_state);
-    _mav_put_uint8_t(buf, 33, venting_valve_state);
+    _mav_put_int32_t(buf, 28, log_good);
+    _mav_put_int16_t(buf, 32, log_number);
+    _mav_put_uint8_t(buf, 34, main_valve_state);
+    _mav_put_uint8_t(buf, 35, venting_valve_state);
+    _mav_put_uint8_t(buf, 36, hil_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOTOR_TM_LEN);
 #else
@@ -100,9 +110,11 @@ static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t comp
     packet.combustion_chamber_pressure = combustion_chamber_pressure;
     packet.tank_temperature = tank_temperature;
     packet.battery_voltage = battery_voltage;
-    packet.current_consumption = current_consumption;
+    packet.log_good = log_good;
+    packet.log_number = log_number;
     packet.main_valve_state = main_valve_state;
     packet.venting_valve_state = venting_valve_state;
+    packet.hil_state = hil_state;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOTOR_TM_LEN);
 #endif
@@ -125,12 +137,14 @@ static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t comp
  * @param main_valve_state  1 If the main valve is open 
  * @param venting_valve_state  1 If the venting valve is open 
  * @param battery_voltage [V] Battery voltage
- * @param current_consumption [A] Current drained from the battery
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param log_good  0 if log failed, 1 otherwise
+ * @param hil_state  1 if the board is currently in HIL mode
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,float top_tank_pressure,float bottom_tank_pressure,float combustion_chamber_pressure,float tank_temperature,uint8_t main_valve_state,uint8_t venting_valve_state,float battery_voltage,float current_consumption)
+                                   uint64_t timestamp,float top_tank_pressure,float bottom_tank_pressure,float combustion_chamber_pressure,float tank_temperature,uint8_t main_valve_state,uint8_t venting_valve_state,float battery_voltage,int16_t log_number,int32_t log_good,uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
@@ -140,9 +154,11 @@ static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t
     _mav_put_float(buf, 16, combustion_chamber_pressure);
     _mav_put_float(buf, 20, tank_temperature);
     _mav_put_float(buf, 24, battery_voltage);
-    _mav_put_float(buf, 28, current_consumption);
-    _mav_put_uint8_t(buf, 32, main_valve_state);
-    _mav_put_uint8_t(buf, 33, venting_valve_state);
+    _mav_put_int32_t(buf, 28, log_good);
+    _mav_put_int16_t(buf, 32, log_number);
+    _mav_put_uint8_t(buf, 34, main_valve_state);
+    _mav_put_uint8_t(buf, 35, venting_valve_state);
+    _mav_put_uint8_t(buf, 36, hil_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOTOR_TM_LEN);
 #else
@@ -153,9 +169,11 @@ static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t
     packet.combustion_chamber_pressure = combustion_chamber_pressure;
     packet.tank_temperature = tank_temperature;
     packet.battery_voltage = battery_voltage;
-    packet.current_consumption = current_consumption;
+    packet.log_good = log_good;
+    packet.log_number = log_number;
     packet.main_valve_state = main_valve_state;
     packet.venting_valve_state = venting_valve_state;
+    packet.hil_state = hil_state;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOTOR_TM_LEN);
 #endif
@@ -174,7 +192,7 @@ static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t
  */
 static inline uint16_t mavlink_msg_motor_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_motor_tm_t* motor_tm)
 {
-    return mavlink_msg_motor_tm_pack(system_id, component_id, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->current_consumption);
+    return mavlink_msg_motor_tm_pack(system_id, component_id, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->log_number, motor_tm->log_good, motor_tm->hil_state);
 }
 
 /**
@@ -188,7 +206,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->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->current_consumption);
+    return mavlink_msg_motor_tm_pack_chan(system_id, component_id, chan, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->log_number, motor_tm->log_good, motor_tm->hil_state);
 }
 
 /**
@@ -203,11 +221,13 @@ static inline uint16_t mavlink_msg_motor_tm_encode_chan(uint8_t system_id, uint8
  * @param main_valve_state  1 If the main valve is open 
  * @param venting_valve_state  1 If the venting valve is open 
  * @param battery_voltage [V] Battery voltage
- * @param current_consumption [A] Current drained from the battery
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param log_good  0 if log failed, 1 otherwise
+ * @param hil_state  1 if the board is currently in HIL mode
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, float current_consumption)
+static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, int16_t log_number, int32_t log_good, uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
@@ -217,9 +237,11 @@ static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t ti
     _mav_put_float(buf, 16, combustion_chamber_pressure);
     _mav_put_float(buf, 20, tank_temperature);
     _mav_put_float(buf, 24, battery_voltage);
-    _mav_put_float(buf, 28, current_consumption);
-    _mav_put_uint8_t(buf, 32, main_valve_state);
-    _mav_put_uint8_t(buf, 33, venting_valve_state);
+    _mav_put_int32_t(buf, 28, log_good);
+    _mav_put_int16_t(buf, 32, log_number);
+    _mav_put_uint8_t(buf, 34, main_valve_state);
+    _mav_put_uint8_t(buf, 35, venting_valve_state);
+    _mav_put_uint8_t(buf, 36, hil_state);
 
     _mav_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
@@ -230,9 +252,11 @@ static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t ti
     packet.combustion_chamber_pressure = combustion_chamber_pressure;
     packet.tank_temperature = tank_temperature;
     packet.battery_voltage = battery_voltage;
-    packet.current_consumption = current_consumption;
+    packet.log_good = log_good;
+    packet.log_number = log_number;
     packet.main_valve_state = main_valve_state;
     packet.venting_valve_state = venting_valve_state;
+    packet.hil_state = hil_state;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, (const char *)&packet, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
 #endif
@@ -246,7 +270,7 @@ static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t ti
 static inline void mavlink_msg_motor_tm_send_struct(mavlink_channel_t chan, const mavlink_motor_tm_t* motor_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_motor_tm_send(chan, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->current_consumption);
+    mavlink_msg_motor_tm_send(chan, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->log_number, motor_tm->log_good, motor_tm->hil_state);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, (const char *)motor_tm, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
 #endif
@@ -260,7 +284,7 @@ static inline void mavlink_msg_motor_tm_send_struct(mavlink_channel_t chan, cons
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_motor_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, float current_consumption)
+static inline void mavlink_msg_motor_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, int16_t log_number, int32_t log_good, uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -270,9 +294,11 @@ static inline void mavlink_msg_motor_tm_send_buf(mavlink_message_t *msgbuf, mavl
     _mav_put_float(buf, 16, combustion_chamber_pressure);
     _mav_put_float(buf, 20, tank_temperature);
     _mav_put_float(buf, 24, battery_voltage);
-    _mav_put_float(buf, 28, current_consumption);
-    _mav_put_uint8_t(buf, 32, main_valve_state);
-    _mav_put_uint8_t(buf, 33, venting_valve_state);
+    _mav_put_int32_t(buf, 28, log_good);
+    _mav_put_int16_t(buf, 32, log_number);
+    _mav_put_uint8_t(buf, 34, main_valve_state);
+    _mav_put_uint8_t(buf, 35, venting_valve_state);
+    _mav_put_uint8_t(buf, 36, hil_state);
 
     _mav_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
@@ -283,9 +309,11 @@ static inline void mavlink_msg_motor_tm_send_buf(mavlink_message_t *msgbuf, mavl
     packet->combustion_chamber_pressure = combustion_chamber_pressure;
     packet->tank_temperature = tank_temperature;
     packet->battery_voltage = battery_voltage;
-    packet->current_consumption = current_consumption;
+    packet->log_good = log_good;
+    packet->log_number = log_number;
     packet->main_valve_state = main_valve_state;
     packet->venting_valve_state = venting_valve_state;
+    packet->hil_state = hil_state;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, (const char *)packet, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
 #endif
@@ -354,7 +382,7 @@ static inline float mavlink_msg_motor_tm_get_tank_temperature(const mavlink_mess
  */
 static inline uint8_t mavlink_msg_motor_tm_get_main_valve_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  32);
+    return _MAV_RETURN_uint8_t(msg,  34);
 }
 
 /**
@@ -364,7 +392,7 @@ static inline uint8_t mavlink_msg_motor_tm_get_main_valve_state(const mavlink_me
  */
 static inline uint8_t mavlink_msg_motor_tm_get_venting_valve_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  33);
+    return _MAV_RETURN_uint8_t(msg,  35);
 }
 
 /**
@@ -378,13 +406,33 @@ static inline float mavlink_msg_motor_tm_get_battery_voltage(const mavlink_messa
 }
 
 /**
- * @brief Get field current_consumption from motor_tm message
+ * @brief Get field log_number from motor_tm message
  *
- * @return [A] Current drained from the battery
+ * @return  Currently active log file, -1 if the logger is inactive
  */
-static inline float mavlink_msg_motor_tm_get_current_consumption(const mavlink_message_t* msg)
+static inline int16_t mavlink_msg_motor_tm_get_log_number(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  28);
+    return _MAV_RETURN_int16_t(msg,  32);
+}
+
+/**
+ * @brief Get field log_good from motor_tm message
+ *
+ * @return  0 if log failed, 1 otherwise
+ */
+static inline int32_t mavlink_msg_motor_tm_get_log_good(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  28);
+}
+
+/**
+ * @brief Get field hil_state from motor_tm message
+ *
+ * @return  1 if the board is currently in HIL mode
+ */
+static inline uint8_t mavlink_msg_motor_tm_get_hil_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  36);
 }
 
 /**
@@ -402,9 +450,11 @@ static inline void mavlink_msg_motor_tm_decode(const mavlink_message_t* msg, mav
     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->log_good = mavlink_msg_motor_tm_get_log_good(msg);
+    motor_tm->log_number = mavlink_msg_motor_tm_get_log_number(msg);
     motor_tm->main_valve_state = mavlink_msg_motor_tm_get_main_valve_state(msg);
     motor_tm->venting_valve_state = mavlink_msg_motor_tm_get_venting_valve_state(msg);
+    motor_tm->hil_state = mavlink_msg_motor_tm_get_hil_state(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_MOTOR_TM_LEN? msg->len : MAVLINK_MSG_ID_MOTOR_TM_LEN;
         memset(motor_tm, 0, MAVLINK_MSG_ID_MOTOR_TM_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_nack_tm.h b/mavlink_lib/lyra/mavlink_msg_nack_tm.h
index 85abd048c50911cd99ded380f566cf5c34b29322..ecbddd6542c2960a72522b01514efc333a845e75 100644
--- a/mavlink_lib/lyra/mavlink_msg_nack_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_nack_tm.h
@@ -5,17 +5,18 @@
 
 
 typedef struct __mavlink_nack_tm_t {
+ uint16_t err_id; /*<  Error core that generated the NACK*/
  uint8_t recv_msgid; /*<  Message id of the received message*/
  uint8_t seq_ack; /*<  Sequence number of the received message*/
 } mavlink_nack_tm_t;
 
-#define MAVLINK_MSG_ID_NACK_TM_LEN 2
-#define MAVLINK_MSG_ID_NACK_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_101_LEN 2
-#define MAVLINK_MSG_ID_101_MIN_LEN 2
+#define MAVLINK_MSG_ID_NACK_TM_LEN 4
+#define MAVLINK_MSG_ID_NACK_TM_MIN_LEN 4
+#define MAVLINK_MSG_ID_101_LEN 4
+#define MAVLINK_MSG_ID_101_MIN_LEN 4
 
-#define MAVLINK_MSG_ID_NACK_TM_CRC 146
-#define MAVLINK_MSG_ID_101_CRC 146
+#define MAVLINK_MSG_ID_NACK_TM_CRC 251
+#define MAVLINK_MSG_ID_101_CRC 251
 
 
 
@@ -23,17 +24,19 @@ typedef struct __mavlink_nack_tm_t {
 #define MAVLINK_MESSAGE_INFO_NACK_TM { \
     101, \
     "NACK_TM", \
-    2, \
-    {  { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
-         { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nack_tm_t, seq_ack) }, \
+    3, \
+    {  { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
+         { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_nack_tm_t, seq_ack) }, \
+         { "err_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_nack_tm_t, err_id) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_NACK_TM { \
     "NACK_TM", \
-    2, \
-    {  { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
-         { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nack_tm_t, seq_ack) }, \
+    3, \
+    {  { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
+         { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_nack_tm_t, seq_ack) }, \
+         { "err_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_nack_tm_t, err_id) }, \
          } \
 }
 #endif
@@ -46,19 +49,22 @@ typedef struct __mavlink_nack_tm_t {
  *
  * @param recv_msgid  Message id of the received message
  * @param seq_ack  Sequence number of the received message
+ * @param err_id  Error core that generated the NACK
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_nack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint8_t recv_msgid, uint8_t seq_ack)
+                               uint8_t recv_msgid, uint8_t seq_ack, uint16_t err_id)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
-    _mav_put_uint8_t(buf, 0, recv_msgid);
-    _mav_put_uint8_t(buf, 1, seq_ack);
+    _mav_put_uint16_t(buf, 0, err_id);
+    _mav_put_uint8_t(buf, 2, recv_msgid);
+    _mav_put_uint8_t(buf, 3, seq_ack);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
 #else
     mavlink_nack_tm_t packet;
+    packet.err_id = err_id;
     packet.recv_msgid = recv_msgid;
     packet.seq_ack = seq_ack;
 
@@ -77,20 +83,23 @@ static inline uint16_t mavlink_msg_nack_tm_pack(uint8_t system_id, uint8_t compo
  * @param msg The MAVLink message to compress the data into
  * @param recv_msgid  Message id of the received message
  * @param seq_ack  Sequence number of the received message
+ * @param err_id  Error core that generated the NACK
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_nack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint8_t recv_msgid,uint8_t seq_ack)
+                                   uint8_t recv_msgid,uint8_t seq_ack,uint16_t err_id)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
-    _mav_put_uint8_t(buf, 0, recv_msgid);
-    _mav_put_uint8_t(buf, 1, seq_ack);
+    _mav_put_uint16_t(buf, 0, err_id);
+    _mav_put_uint8_t(buf, 2, recv_msgid);
+    _mav_put_uint8_t(buf, 3, seq_ack);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
 #else
     mavlink_nack_tm_t packet;
+    packet.err_id = err_id;
     packet.recv_msgid = recv_msgid;
     packet.seq_ack = seq_ack;
 
@@ -111,7 +120,7 @@ static inline uint16_t mavlink_msg_nack_tm_pack_chan(uint8_t system_id, uint8_t
  */
 static inline uint16_t mavlink_msg_nack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
 {
-    return mavlink_msg_nack_tm_pack(system_id, component_id, msg, nack_tm->recv_msgid, nack_tm->seq_ack);
+    return mavlink_msg_nack_tm_pack(system_id, component_id, msg, nack_tm->recv_msgid, nack_tm->seq_ack, nack_tm->err_id);
 }
 
 /**
@@ -125,7 +134,7 @@ static inline uint16_t mavlink_msg_nack_tm_encode(uint8_t system_id, uint8_t com
  */
 static inline uint16_t mavlink_msg_nack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
 {
-    return mavlink_msg_nack_tm_pack_chan(system_id, component_id, chan, msg, nack_tm->recv_msgid, nack_tm->seq_ack);
+    return mavlink_msg_nack_tm_pack_chan(system_id, component_id, chan, msg, nack_tm->recv_msgid, nack_tm->seq_ack, nack_tm->err_id);
 }
 
 /**
@@ -134,19 +143,22 @@ static inline uint16_t mavlink_msg_nack_tm_encode_chan(uint8_t system_id, uint8_
  *
  * @param recv_msgid  Message id of the received message
  * @param seq_ack  Sequence number of the received message
+ * @param err_id  Error core that generated the NACK
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_nack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
+static inline void mavlink_msg_nack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack, uint16_t err_id)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
-    _mav_put_uint8_t(buf, 0, recv_msgid);
-    _mav_put_uint8_t(buf, 1, seq_ack);
+    _mav_put_uint16_t(buf, 0, err_id);
+    _mav_put_uint8_t(buf, 2, recv_msgid);
+    _mav_put_uint8_t(buf, 3, seq_ack);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, buf, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
 #else
     mavlink_nack_tm_t packet;
+    packet.err_id = err_id;
     packet.recv_msgid = recv_msgid;
     packet.seq_ack = seq_ack;
 
@@ -162,7 +174,7 @@ static inline void mavlink_msg_nack_tm_send(mavlink_channel_t chan, uint8_t recv
 static inline void mavlink_msg_nack_tm_send_struct(mavlink_channel_t chan, const mavlink_nack_tm_t* nack_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_nack_tm_send(chan, nack_tm->recv_msgid, nack_tm->seq_ack);
+    mavlink_msg_nack_tm_send(chan, nack_tm->recv_msgid, nack_tm->seq_ack, nack_tm->err_id);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)nack_tm, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
 #endif
@@ -176,16 +188,18 @@ static inline void mavlink_msg_nack_tm_send_struct(mavlink_channel_t chan, const
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_nack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t recv_msgid, uint8_t seq_ack)
+static inline void mavlink_msg_nack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t recv_msgid, uint8_t seq_ack, uint16_t err_id)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
-    _mav_put_uint8_t(buf, 0, recv_msgid);
-    _mav_put_uint8_t(buf, 1, seq_ack);
+    _mav_put_uint16_t(buf, 0, err_id);
+    _mav_put_uint8_t(buf, 2, recv_msgid);
+    _mav_put_uint8_t(buf, 3, seq_ack);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, buf, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
 #else
     mavlink_nack_tm_t *packet = (mavlink_nack_tm_t *)msgbuf;
+    packet->err_id = err_id;
     packet->recv_msgid = recv_msgid;
     packet->seq_ack = seq_ack;
 
@@ -206,7 +220,7 @@ static inline void mavlink_msg_nack_tm_send_buf(mavlink_message_t *msgbuf, mavli
  */
 static inline uint8_t mavlink_msg_nack_tm_get_recv_msgid(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  0);
+    return _MAV_RETURN_uint8_t(msg,  2);
 }
 
 /**
@@ -216,7 +230,17 @@ static inline uint8_t mavlink_msg_nack_tm_get_recv_msgid(const mavlink_message_t
  */
 static inline uint8_t mavlink_msg_nack_tm_get_seq_ack(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  1);
+    return _MAV_RETURN_uint8_t(msg,  3);
+}
+
+/**
+ * @brief Get field err_id from nack_tm message
+ *
+ * @return  Error core that generated the NACK
+ */
+static inline uint16_t mavlink_msg_nack_tm_get_err_id(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  0);
 }
 
 /**
@@ -228,6 +252,7 @@ static inline uint8_t mavlink_msg_nack_tm_get_seq_ack(const mavlink_message_t* m
 static inline void mavlink_msg_nack_tm_decode(const mavlink_message_t* msg, mavlink_nack_tm_t* nack_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    nack_tm->err_id = mavlink_msg_nack_tm_get_err_id(msg);
     nack_tm->recv_msgid = mavlink_msg_nack_tm_get_recv_msgid(msg);
     nack_tm->seq_ack = mavlink_msg_nack_tm_get_seq_ack(msg);
 #else
diff --git a/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h b/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h
index bfe077c3582106f59cfe4d17c86e22f178d0d299..425b48fde287a3daf2877b78cafe9c6bf3de0f88 100644
--- a/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h
@@ -24,41 +24,40 @@ typedef struct __mavlink_payload_flight_tm_t {
  float gps_alt; /*< [m] GPS Altitude*/
  float left_servo_angle; /*< [deg] Left servo motor angle*/
  float right_servo_angle; /*< [deg] Right servo motor angle*/
- 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*/
- float nas_vn; /*< [m/s] Navigation system estimated north velocity*/
- float nas_ve; /*< [m/s] Navigation system estimated east velocity*/
- float nas_vd; /*< [m/s] Navigation system estimated down velocity*/
- float nas_qx; /*< [deg] Navigation system estimated attitude (qx)*/
- float nas_qy; /*< [deg] Navigation system estimated attitude (qy)*/
- float nas_qz; /*< [deg] Navigation system estimated attitude (qz)*/
- float nas_qw; /*< [deg] Navigation system estimated attitude (qw)*/
- 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 nas_n; /*< [deg] NAS estimated noth position*/
+ float nas_e; /*< [deg] NAS estimated east position*/
+ float nas_d; /*< [m] NAS estimated down position*/
+ float nas_vn; /*< [m/s] NAS estimated north velocity*/
+ float nas_ve; /*< [m/s] NAS estimated east velocity*/
+ float nas_vd; /*< [m/s] NAS estimated down velocity*/
+ float nas_qx; /*< [deg] NAS estimated attitude (qx)*/
+ float nas_qy; /*< [deg] NAS estimated attitude (qy)*/
+ float nas_qz; /*< [deg] NAS estimated attitude (qz)*/
+ float nas_qw; /*< [deg] NAS estimated attitude (qw)*/
+ float nas_bias_x; /*<  NAS gyroscope bias on x axis*/
+ float nas_bias_y; /*<  NAS gyroscope bias on y axis*/
+ float nas_bias_z; /*<  NAS gyroscope bias on z axis*/
  float wes_n; /*< [m/s] Wind estimated north velocity*/
  float wes_e; /*< [m/s] Wind estimated east velocity*/
  float battery_voltage; /*< [V] Battery voltage*/
  float cam_battery_voltage; /*< [V] Camera battery voltage*/
- float current_consumption; /*< [A] Battery current*/
  float temperature; /*< [degC] Temperature*/
  uint8_t fmm_state; /*<  Flight Mode Manager State*/
- uint8_t nas_state; /*<  Navigation System FSM State*/
+ uint8_t nas_state; /*<  NAS FSM State*/
  uint8_t wes_state; /*<  Wind Estimation System FSM State*/
  uint8_t gps_fix; /*<  GPS fix (1 = fix, 0 = no fix)*/
+ uint8_t pin_launch; /*<  Launch pin status (1 = connected, 0 = disconnected)*/
  uint8_t pin_nosecone; /*<  Nosecone pin status (1 = connected, 0 = disconnected)*/
  uint8_t cutter_presence; /*<  Cutter presence status (1 = present, 0 = missing)*/
- int8_t logger_error; /*<  Logger error (0 = no error)*/
 } mavlink_payload_flight_tm_t;
 
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN 163
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN 163
-#define MAVLINK_MSG_ID_209_LEN 163
-#define MAVLINK_MSG_ID_209_MIN_LEN 163
+#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN 159
+#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN 159
+#define MAVLINK_MSG_ID_209_LEN 159
+#define MAVLINK_MSG_ID_209_MIN_LEN 159
 
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC 84
-#define MAVLINK_MSG_ID_209_CRC 84
+#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC 59
+#define MAVLINK_MSG_ID_209_CRC 59
 
 
 
@@ -66,11 +65,11 @@ typedef struct __mavlink_payload_flight_tm_t {
 #define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \
     209, \
     "PAYLOAD_FLIGHT_TM", \
-    45, \
+    44, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
-         { "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) }, \
+         { "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) }, \
          { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \
          { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \
          { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \
@@ -84,7 +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, 159, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 155, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
          { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
          { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
          { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
@@ -105,23 +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, 160, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
+         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, pin_launch) }, \
+         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
+         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_flight_tm_t, cutter_presence) }, \
          { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, battery_voltage) }, \
          { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, cam_battery_voltage) }, \
-         { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, current_consumption) }, \
-         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, cutter_presence) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
-         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 162, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \
     "PAYLOAD_FLIGHT_TM", \
-    45, \
+    44, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
-         { "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) }, \
+         { "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) }, \
          { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \
          { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \
          { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \
@@ -135,7 +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, 159, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 155, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
          { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
          { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
          { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
@@ -156,13 +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, 160, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
+         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, pin_launch) }, \
+         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
+         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_flight_tm_t, cutter_presence) }, \
          { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, battery_voltage) }, \
          { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, cam_battery_voltage) }, \
-         { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, current_consumption) }, \
-         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, cutter_presence) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
-         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 162, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
          } \
 }
 #endif
@@ -175,7 +172,7 @@ typedef struct __mavlink_payload_flight_tm_t {
  *
  * @param timestamp [us] Timestamp in microseconds
  * @param fmm_state  Flight Mode Manager State
- * @param nas_state  Navigation System FSM State
+ * @param nas_state  NAS FSM State
  * @param wes_state  Wind Estimation System FSM State
  * @param pressure_digi [Pa] Pressure from digital sensor
  * @param pressure_static [Pa] Pressure from static port
@@ -196,32 +193,31 @@ typedef struct __mavlink_payload_flight_tm_t {
  * @param gps_alt [m] GPS Altitude
  * @param left_servo_angle [deg] Left servo motor angle
  * @param right_servo_angle [deg] Right servo motor angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x  Navigation system gyroscope bias on x axis
- * @param nas_bias_y  Navigation system gyroscope bias on y axis
- * @param nas_bias_z  Navigation system gyroscope bias on z axis
+ * @param nas_n [deg] NAS estimated noth position
+ * @param nas_e [deg] NAS estimated east position
+ * @param nas_d [m] NAS estimated down position
+ * @param nas_vn [m/s] NAS estimated north velocity
+ * @param nas_ve [m/s] NAS estimated east velocity
+ * @param nas_vd [m/s] NAS estimated down velocity
+ * @param nas_qx [deg] NAS estimated attitude (qx)
+ * @param nas_qy [deg] NAS estimated attitude (qy)
+ * @param nas_qz [deg] NAS estimated attitude (qz)
+ * @param nas_qw [deg] NAS estimated attitude (qw)
+ * @param nas_bias_x  NAS gyroscope bias on x axis
+ * @param nas_bias_y  NAS gyroscope bias on y axis
+ * @param nas_bias_z  NAS gyroscope bias on z axis
  * @param wes_n [m/s] Wind estimated north velocity
  * @param wes_e [m/s] Wind estimated east velocity
+ * @param pin_launch  Launch pin status (1 = connected, 0 = disconnected)
  * @param pin_nosecone  Nosecone pin status (1 = connected, 0 = disconnected)
+ * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
  * @param battery_voltage [V] Battery voltage
  * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
  * @param temperature [degC] Temperature
- * @param logger_error  Logger error (0 = no error)
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, uint8_t cutter_presence, 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_launch, uint8_t pin_nosecone, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float temperature)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
@@ -261,15 +257,14 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
     _mav_put_float(buf, 136, wes_e);
     _mav_put_float(buf, 140, battery_voltage);
     _mav_put_float(buf, 144, cam_battery_voltage);
-    _mav_put_float(buf, 148, current_consumption);
-    _mav_put_float(buf, 152, temperature);
-    _mav_put_uint8_t(buf, 156, fmm_state);
-    _mav_put_uint8_t(buf, 157, nas_state);
-    _mav_put_uint8_t(buf, 158, wes_state);
-    _mav_put_uint8_t(buf, 159, gps_fix);
-    _mav_put_uint8_t(buf, 160, pin_nosecone);
-    _mav_put_uint8_t(buf, 161, cutter_presence);
-    _mav_put_int8_t(buf, 162, logger_error);
+    _mav_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_launch);
+    _mav_put_uint8_t(buf, 157, pin_nosecone);
+    _mav_put_uint8_t(buf, 158, cutter_presence);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
 #else
@@ -310,15 +305,14 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
     packet.wes_e = wes_e;
     packet.battery_voltage = battery_voltage;
     packet.cam_battery_voltage = cam_battery_voltage;
-    packet.current_consumption = current_consumption;
     packet.temperature = temperature;
     packet.fmm_state = fmm_state;
     packet.nas_state = nas_state;
     packet.wes_state = wes_state;
     packet.gps_fix = gps_fix;
+    packet.pin_launch = pin_launch;
     packet.pin_nosecone = pin_nosecone;
     packet.cutter_presence = cutter_presence;
-    packet.logger_error = logger_error;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
 #endif
@@ -335,7 +329,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
  * @param msg The MAVLink message to compress the data into
  * @param timestamp [us] Timestamp in microseconds
  * @param fmm_state  Flight Mode Manager State
- * @param nas_state  Navigation System FSM State
+ * @param nas_state  NAS FSM State
  * @param wes_state  Wind Estimation System FSM State
  * @param pressure_digi [Pa] Pressure from digital sensor
  * @param pressure_static [Pa] Pressure from static port
@@ -356,33 +350,32 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
  * @param gps_alt [m] GPS Altitude
  * @param left_servo_angle [deg] Left servo motor angle
  * @param right_servo_angle [deg] Right servo motor angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x  Navigation system gyroscope bias on x axis
- * @param nas_bias_y  Navigation system gyroscope bias on y axis
- * @param nas_bias_z  Navigation system gyroscope bias on z axis
+ * @param nas_n [deg] NAS estimated noth position
+ * @param nas_e [deg] NAS estimated east position
+ * @param nas_d [m] NAS estimated down position
+ * @param nas_vn [m/s] NAS estimated north velocity
+ * @param nas_ve [m/s] NAS estimated east velocity
+ * @param nas_vd [m/s] NAS estimated down velocity
+ * @param nas_qx [deg] NAS estimated attitude (qx)
+ * @param nas_qy [deg] NAS estimated attitude (qy)
+ * @param nas_qz [deg] NAS estimated attitude (qz)
+ * @param nas_qw [deg] NAS estimated attitude (qw)
+ * @param nas_bias_x  NAS gyroscope bias on x axis
+ * @param nas_bias_y  NAS gyroscope bias on y axis
+ * @param nas_bias_z  NAS gyroscope bias on z axis
  * @param wes_n [m/s] Wind estimated north velocity
  * @param wes_e [m/s] Wind estimated east velocity
+ * @param pin_launch  Launch pin status (1 = connected, 0 = disconnected)
  * @param pin_nosecone  Nosecone pin status (1 = connected, 0 = disconnected)
+ * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
  * @param battery_voltage [V] Battery voltage
  * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
  * @param temperature [degC] Temperature
- * @param logger_error  Logger error (0 = no error)
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,uint8_t fmm_state,uint8_t nas_state,uint8_t wes_state,float pressure_digi,float pressure_static,float airspeed_pitot,float altitude_agl,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float left_servo_angle,float right_servo_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float wes_n,float wes_e,uint8_t pin_nosecone,float battery_voltage,float cam_battery_voltage,float current_consumption,uint8_t cutter_presence,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_launch,uint8_t pin_nosecone,uint8_t cutter_presence,float battery_voltage,float cam_battery_voltage,float temperature)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
@@ -422,15 +415,14 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id
     _mav_put_float(buf, 136, wes_e);
     _mav_put_float(buf, 140, battery_voltage);
     _mav_put_float(buf, 144, cam_battery_voltage);
-    _mav_put_float(buf, 148, current_consumption);
-    _mav_put_float(buf, 152, temperature);
-    _mav_put_uint8_t(buf, 156, fmm_state);
-    _mav_put_uint8_t(buf, 157, nas_state);
-    _mav_put_uint8_t(buf, 158, wes_state);
-    _mav_put_uint8_t(buf, 159, gps_fix);
-    _mav_put_uint8_t(buf, 160, pin_nosecone);
-    _mav_put_uint8_t(buf, 161, cutter_presence);
-    _mav_put_int8_t(buf, 162, logger_error);
+    _mav_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_launch);
+    _mav_put_uint8_t(buf, 157, pin_nosecone);
+    _mav_put_uint8_t(buf, 158, cutter_presence);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
 #else
@@ -471,15 +463,14 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id
     packet.wes_e = wes_e;
     packet.battery_voltage = battery_voltage;
     packet.cam_battery_voltage = cam_battery_voltage;
-    packet.current_consumption = current_consumption;
     packet.temperature = temperature;
     packet.fmm_state = fmm_state;
     packet.nas_state = nas_state;
     packet.wes_state = wes_state;
     packet.gps_fix = gps_fix;
+    packet.pin_launch = pin_launch;
     packet.pin_nosecone = pin_nosecone;
     packet.cutter_presence = cutter_presence;
-    packet.logger_error = logger_error;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
 #endif
@@ -498,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->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->logger_error);
+    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_launch, payload_flight_tm->pin_nosecone, payload_flight_tm->cutter_presence, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->temperature);
 }
 
 /**
@@ -512,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->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->logger_error);
+    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_launch, payload_flight_tm->pin_nosecone, payload_flight_tm->cutter_presence, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->temperature);
 }
 
 /**
@@ -521,7 +512,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_
  *
  * @param timestamp [us] Timestamp in microseconds
  * @param fmm_state  Flight Mode Manager State
- * @param nas_state  Navigation System FSM State
+ * @param nas_state  NAS FSM State
  * @param wes_state  Wind Estimation System FSM State
  * @param pressure_digi [Pa] Pressure from digital sensor
  * @param pressure_static [Pa] Pressure from static port
@@ -542,32 +533,31 @@ static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_
  * @param gps_alt [m] GPS Altitude
  * @param left_servo_angle [deg] Left servo motor angle
  * @param right_servo_angle [deg] Right servo motor angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x  Navigation system gyroscope bias on x axis
- * @param nas_bias_y  Navigation system gyroscope bias on y axis
- * @param nas_bias_z  Navigation system gyroscope bias on z axis
+ * @param nas_n [deg] NAS estimated noth position
+ * @param nas_e [deg] NAS estimated east position
+ * @param nas_d [m] NAS estimated down position
+ * @param nas_vn [m/s] NAS estimated north velocity
+ * @param nas_ve [m/s] NAS estimated east velocity
+ * @param nas_vd [m/s] NAS estimated down velocity
+ * @param nas_qx [deg] NAS estimated attitude (qx)
+ * @param nas_qy [deg] NAS estimated attitude (qy)
+ * @param nas_qz [deg] NAS estimated attitude (qz)
+ * @param nas_qw [deg] NAS estimated attitude (qw)
+ * @param nas_bias_x  NAS gyroscope bias on x axis
+ * @param nas_bias_y  NAS gyroscope bias on y axis
+ * @param nas_bias_z  NAS gyroscope bias on z axis
  * @param wes_n [m/s] Wind estimated north velocity
  * @param wes_e [m/s] Wind estimated east velocity
+ * @param pin_launch  Launch pin status (1 = connected, 0 = disconnected)
  * @param pin_nosecone  Nosecone pin status (1 = connected, 0 = disconnected)
+ * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
  * @param battery_voltage [V] Battery voltage
  * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
  * @param temperature [degC] Temperature
- * @param logger_error  Logger error (0 = no error)
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, uint8_t cutter_presence, 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_launch, uint8_t pin_nosecone, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float temperature)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
@@ -607,15 +597,14 @@ static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, ui
     _mav_put_float(buf, 136, wes_e);
     _mav_put_float(buf, 140, battery_voltage);
     _mav_put_float(buf, 144, cam_battery_voltage);
-    _mav_put_float(buf, 148, current_consumption);
-    _mav_put_float(buf, 152, temperature);
-    _mav_put_uint8_t(buf, 156, fmm_state);
-    _mav_put_uint8_t(buf, 157, nas_state);
-    _mav_put_uint8_t(buf, 158, wes_state);
-    _mav_put_uint8_t(buf, 159, gps_fix);
-    _mav_put_uint8_t(buf, 160, pin_nosecone);
-    _mav_put_uint8_t(buf, 161, cutter_presence);
-    _mav_put_int8_t(buf, 162, logger_error);
+    _mav_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_launch);
+    _mav_put_uint8_t(buf, 157, pin_nosecone);
+    _mav_put_uint8_t(buf, 158, cutter_presence);
 
     _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
@@ -656,15 +645,14 @@ static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, ui
     packet.wes_e = wes_e;
     packet.battery_voltage = battery_voltage;
     packet.cam_battery_voltage = cam_battery_voltage;
-    packet.current_consumption = current_consumption;
     packet.temperature = temperature;
     packet.fmm_state = fmm_state;
     packet.nas_state = nas_state;
     packet.wes_state = wes_state;
     packet.gps_fix = gps_fix;
+    packet.pin_launch = pin_launch;
     packet.pin_nosecone = pin_nosecone;
     packet.cutter_presence = cutter_presence;
-    packet.logger_error = logger_error;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)&packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
 #endif
@@ -678,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->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->logger_error);
+    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_launch, payload_flight_tm->pin_nosecone, payload_flight_tm->cutter_presence, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->temperature);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)payload_flight_tm, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
 #endif
@@ -692,7 +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 battery_voltage, float cam_battery_voltage, float current_consumption, uint8_t cutter_presence, 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_launch, uint8_t pin_nosecone, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float temperature)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -732,15 +720,14 @@ static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msg
     _mav_put_float(buf, 136, wes_e);
     _mav_put_float(buf, 140, battery_voltage);
     _mav_put_float(buf, 144, cam_battery_voltage);
-    _mav_put_float(buf, 148, current_consumption);
-    _mav_put_float(buf, 152, temperature);
-    _mav_put_uint8_t(buf, 156, fmm_state);
-    _mav_put_uint8_t(buf, 157, nas_state);
-    _mav_put_uint8_t(buf, 158, wes_state);
-    _mav_put_uint8_t(buf, 159, gps_fix);
-    _mav_put_uint8_t(buf, 160, pin_nosecone);
-    _mav_put_uint8_t(buf, 161, cutter_presence);
-    _mav_put_int8_t(buf, 162, logger_error);
+    _mav_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_launch);
+    _mav_put_uint8_t(buf, 157, pin_nosecone);
+    _mav_put_uint8_t(buf, 158, cutter_presence);
 
     _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
@@ -781,15 +768,14 @@ static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msg
     packet->wes_e = wes_e;
     packet->battery_voltage = battery_voltage;
     packet->cam_battery_voltage = cam_battery_voltage;
-    packet->current_consumption = current_consumption;
     packet->temperature = temperature;
     packet->fmm_state = fmm_state;
     packet->nas_state = nas_state;
     packet->wes_state = wes_state;
     packet->gps_fix = gps_fix;
+    packet->pin_launch = pin_launch;
     packet->pin_nosecone = pin_nosecone;
     packet->cutter_presence = cutter_presence;
-    packet->logger_error = logger_error;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
 #endif
@@ -818,17 +804,17 @@ 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,  156);
+    return _MAV_RETURN_uint8_t(msg,  152);
 }
 
 /**
  * @brief Get field nas_state from payload_flight_tm message
  *
- * @return  Navigation System FSM State
+ * @return  NAS FSM State
  */
 static inline uint8_t mavlink_msg_payload_flight_tm_get_nas_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  157);
+    return _MAV_RETURN_uint8_t(msg,  153);
 }
 
 /**
@@ -838,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,  158);
+    return _MAV_RETURN_uint8_t(msg,  154);
 }
 
 /**
@@ -978,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,  159);
+    return _MAV_RETURN_uint8_t(msg,  155);
 }
 
 /**
@@ -1034,7 +1020,7 @@ static inline float mavlink_msg_payload_flight_tm_get_right_servo_angle(const ma
 /**
  * @brief Get field nas_n from payload_flight_tm message
  *
- * @return [deg] Navigation system estimated noth position
+ * @return [deg] NAS estimated noth position
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_n(const mavlink_message_t* msg)
 {
@@ -1044,7 +1030,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_n(const mavlink_messag
 /**
  * @brief Get field nas_e from payload_flight_tm message
  *
- * @return [deg] Navigation system estimated east position
+ * @return [deg] NAS estimated east position
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_e(const mavlink_message_t* msg)
 {
@@ -1054,7 +1040,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_e(const mavlink_messag
 /**
  * @brief Get field nas_d from payload_flight_tm message
  *
- * @return [m] Navigation system estimated down position
+ * @return [m] NAS estimated down position
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_d(const mavlink_message_t* msg)
 {
@@ -1064,7 +1050,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_d(const mavlink_messag
 /**
  * @brief Get field nas_vn from payload_flight_tm message
  *
- * @return [m/s] Navigation system estimated north velocity
+ * @return [m/s] NAS estimated north velocity
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_vn(const mavlink_message_t* msg)
 {
@@ -1074,7 +1060,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_vn(const mavlink_messa
 /**
  * @brief Get field nas_ve from payload_flight_tm message
  *
- * @return [m/s] Navigation system estimated east velocity
+ * @return [m/s] NAS estimated east velocity
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_ve(const mavlink_message_t* msg)
 {
@@ -1084,7 +1070,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_ve(const mavlink_messa
 /**
  * @brief Get field nas_vd from payload_flight_tm message
  *
- * @return [m/s] Navigation system estimated down velocity
+ * @return [m/s] NAS estimated down velocity
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_vd(const mavlink_message_t* msg)
 {
@@ -1094,7 +1080,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_vd(const mavlink_messa
 /**
  * @brief Get field nas_qx from payload_flight_tm message
  *
- * @return [deg] Navigation system estimated attitude (qx)
+ * @return [deg] NAS estimated attitude (qx)
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_qx(const mavlink_message_t* msg)
 {
@@ -1104,7 +1090,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_qx(const mavlink_messa
 /**
  * @brief Get field nas_qy from payload_flight_tm message
  *
- * @return [deg] Navigation system estimated attitude (qy)
+ * @return [deg] NAS estimated attitude (qy)
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_qy(const mavlink_message_t* msg)
 {
@@ -1114,7 +1100,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_qy(const mavlink_messa
 /**
  * @brief Get field nas_qz from payload_flight_tm message
  *
- * @return [deg] Navigation system estimated attitude (qz)
+ * @return [deg] NAS estimated attitude (qz)
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_qz(const mavlink_message_t* msg)
 {
@@ -1124,7 +1110,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_qz(const mavlink_messa
 /**
  * @brief Get field nas_qw from payload_flight_tm message
  *
- * @return [deg] Navigation system estimated attitude (qw)
+ * @return [deg] NAS estimated attitude (qw)
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_qw(const mavlink_message_t* msg)
 {
@@ -1134,7 +1120,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_qw(const mavlink_messa
 /**
  * @brief Get field nas_bias_x from payload_flight_tm message
  *
- * @return  Navigation system gyroscope bias on x axis
+ * @return  NAS gyroscope bias on x axis
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_bias_x(const mavlink_message_t* msg)
 {
@@ -1144,7 +1130,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_bias_x(const mavlink_m
 /**
  * @brief Get field nas_bias_y from payload_flight_tm message
  *
- * @return  Navigation system gyroscope bias on y axis
+ * @return  NAS gyroscope bias on y axis
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_bias_y(const mavlink_message_t* msg)
 {
@@ -1154,7 +1140,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_bias_y(const mavlink_m
 /**
  * @brief Get field nas_bias_z from payload_flight_tm message
  *
- * @return  Navigation system gyroscope bias on z axis
+ * @return  NAS gyroscope bias on z axis
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_bias_z(const mavlink_message_t* msg)
 {
@@ -1182,53 +1168,53 @@ static inline float mavlink_msg_payload_flight_tm_get_wes_e(const mavlink_messag
 }
 
 /**
- * @brief Get field pin_nosecone from payload_flight_tm message
+ * @brief Get field pin_launch from payload_flight_tm message
  *
- * @return  Nosecone pin status (1 = connected, 0 = disconnected)
+ * @return  Launch pin status (1 = connected, 0 = disconnected)
  */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_pin_nosecone(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_payload_flight_tm_get_pin_launch(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  160);
+    return _MAV_RETURN_uint8_t(msg,  156);
 }
 
 /**
- * @brief Get field battery_voltage from payload_flight_tm message
+ * @brief Get field pin_nosecone from payload_flight_tm message
  *
- * @return [V] Battery voltage
+ * @return  Nosecone pin status (1 = connected, 0 = disconnected)
  */
-static inline float mavlink_msg_payload_flight_tm_get_battery_voltage(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_payload_flight_tm_get_pin_nosecone(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  140);
+    return _MAV_RETURN_uint8_t(msg,  157);
 }
 
 /**
- * @brief Get field cam_battery_voltage from payload_flight_tm message
+ * @brief Get field cutter_presence from payload_flight_tm message
  *
- * @return [V] Camera battery voltage
+ * @return  Cutter presence status (1 = present, 0 = missing)
  */
-static inline float mavlink_msg_payload_flight_tm_get_cam_battery_voltage(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_payload_flight_tm_get_cutter_presence(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  144);
+    return _MAV_RETURN_uint8_t(msg,  158);
 }
 
 /**
- * @brief Get field current_consumption from payload_flight_tm message
+ * @brief Get field battery_voltage from payload_flight_tm message
  *
- * @return [A] Battery current
+ * @return [V] Battery voltage
  */
-static inline float mavlink_msg_payload_flight_tm_get_current_consumption(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,  148);
+    return _MAV_RETURN_float(msg,  140);
 }
 
 /**
- * @brief Get field cutter_presence from payload_flight_tm message
+ * @brief Get field cam_battery_voltage from payload_flight_tm message
  *
- * @return  Cutter presence status (1 = present, 0 = missing)
+ * @return [V] Camera battery voltage
  */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_cutter_presence(const mavlink_message_t* msg)
+static inline float mavlink_msg_payload_flight_tm_get_cam_battery_voltage(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  161);
+    return _MAV_RETURN_float(msg,  144);
 }
 
 /**
@@ -1238,17 +1224,7 @@ static inline uint8_t mavlink_msg_payload_flight_tm_get_cutter_presence(const ma
  */
 static inline float mavlink_msg_payload_flight_tm_get_temperature(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  152);
-}
-
-/**
- * @brief Get field logger_error from payload_flight_tm message
- *
- * @return  Logger error (0 = no error)
- */
-static inline int8_t mavlink_msg_payload_flight_tm_get_logger_error(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_int8_t(msg,  162);
+    return _MAV_RETURN_float(msg,  148);
 }
 
 /**
@@ -1296,15 +1272,14 @@ static inline void mavlink_msg_payload_flight_tm_decode(const mavlink_message_t*
     payload_flight_tm->wes_e = mavlink_msg_payload_flight_tm_get_wes_e(msg);
     payload_flight_tm->battery_voltage = mavlink_msg_payload_flight_tm_get_battery_voltage(msg);
     payload_flight_tm->cam_battery_voltage = mavlink_msg_payload_flight_tm_get_cam_battery_voltage(msg);
-    payload_flight_tm->current_consumption = mavlink_msg_payload_flight_tm_get_current_consumption(msg);
     payload_flight_tm->temperature = mavlink_msg_payload_flight_tm_get_temperature(msg);
     payload_flight_tm->fmm_state = mavlink_msg_payload_flight_tm_get_fmm_state(msg);
     payload_flight_tm->nas_state = mavlink_msg_payload_flight_tm_get_nas_state(msg);
     payload_flight_tm->wes_state = mavlink_msg_payload_flight_tm_get_wes_state(msg);
     payload_flight_tm->gps_fix = mavlink_msg_payload_flight_tm_get_gps_fix(msg);
+    payload_flight_tm->pin_launch = mavlink_msg_payload_flight_tm_get_pin_launch(msg);
     payload_flight_tm->pin_nosecone = mavlink_msg_payload_flight_tm_get_pin_nosecone(msg);
     payload_flight_tm->cutter_presence = mavlink_msg_payload_flight_tm_get_cutter_presence(msg);
-    payload_flight_tm->logger_error = mavlink_msg_payload_flight_tm_get_logger_error(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN? msg->len : MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN;
         memset(payload_flight_tm, 0, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h
index 3b945c4692aa2e834689fd0617809d5f5be22970..d787505382f56d18e6821d2c3b74690db97f2129 100644
--- a/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h
@@ -20,15 +20,23 @@ typedef struct __mavlink_payload_stats_tm_t {
  float min_pressure; /*< [Pa] Apogee pressure - Digital barometer*/
  float cpu_load; /*<  CPU load in percentage*/
  uint32_t free_heap; /*<  Amount of available heap in memory*/
+ int32_t log_good; /*<  0 if log failed, 1 otherwise*/
+ int16_t log_number; /*<  Currently active log file, -1 if the logger is inactive*/
+ uint8_t main_board_state; /*<  Main board fmm state*/
+ uint8_t motor_board_state; /*<  Motor board fmm state*/
+ uint8_t main_can_status; /*<  Main CAN status*/
+ uint8_t motor_can_status; /*<  Motor CAN status*/
+ uint8_t rig_can_status; /*<  RIG CAN status*/
+ uint8_t hil_state; /*<  1 if the board is currently in HIL mode*/
 } mavlink_payload_stats_tm_t;
 
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN 76
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN 76
-#define MAVLINK_MSG_ID_211_LEN 76
-#define MAVLINK_MSG_ID_211_MIN_LEN 76
+#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN 88
+#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN 88
+#define MAVLINK_MSG_ID_211_LEN 88
+#define MAVLINK_MSG_ID_211_MIN_LEN 88
 
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC 115
-#define MAVLINK_MSG_ID_211_CRC 115
+#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC 64
+#define MAVLINK_MSG_ID_211_CRC 64
 
 
 
@@ -36,7 +44,7 @@ typedef struct __mavlink_payload_stats_tm_t {
 #define MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM { \
     211, \
     "PAYLOAD_STATS_TM", \
-    15, \
+    23, \
     {  { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc_ts) }, \
          { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc) }, \
          { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_payload_stats_tm_t, dpl_ts) }, \
@@ -52,12 +60,20 @@ typedef struct __mavlink_payload_stats_tm_t {
          { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_stats_tm_t, min_pressure) }, \
          { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_stats_tm_t, cpu_load) }, \
          { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 72, offsetof(mavlink_payload_stats_tm_t, free_heap) }, \
+         { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 80, offsetof(mavlink_payload_stats_tm_t, log_number) }, \
+         { "log_good", NULL, MAVLINK_TYPE_INT32_T, 0, 76, offsetof(mavlink_payload_stats_tm_t, log_good) }, \
+         { "main_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_payload_stats_tm_t, main_board_state) }, \
+         { "motor_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_payload_stats_tm_t, motor_board_state) }, \
+         { "main_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 84, offsetof(mavlink_payload_stats_tm_t, main_can_status) }, \
+         { "motor_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 85, offsetof(mavlink_payload_stats_tm_t, motor_can_status) }, \
+         { "rig_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 86, offsetof(mavlink_payload_stats_tm_t, rig_can_status) }, \
+         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 87, offsetof(mavlink_payload_stats_tm_t, hil_state) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM { \
     "PAYLOAD_STATS_TM", \
-    15, \
+    23, \
     {  { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc_ts) }, \
          { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc) }, \
          { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_payload_stats_tm_t, dpl_ts) }, \
@@ -73,6 +89,14 @@ typedef struct __mavlink_payload_stats_tm_t {
          { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_stats_tm_t, min_pressure) }, \
          { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_stats_tm_t, cpu_load) }, \
          { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 72, offsetof(mavlink_payload_stats_tm_t, free_heap) }, \
+         { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 80, offsetof(mavlink_payload_stats_tm_t, log_number) }, \
+         { "log_good", NULL, MAVLINK_TYPE_INT32_T, 0, 76, offsetof(mavlink_payload_stats_tm_t, log_good) }, \
+         { "main_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_payload_stats_tm_t, main_board_state) }, \
+         { "motor_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_payload_stats_tm_t, motor_board_state) }, \
+         { "main_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 84, offsetof(mavlink_payload_stats_tm_t, main_can_status) }, \
+         { "motor_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 85, offsetof(mavlink_payload_stats_tm_t, motor_can_status) }, \
+         { "rig_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 86, offsetof(mavlink_payload_stats_tm_t, rig_can_status) }, \
+         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 87, offsetof(mavlink_payload_stats_tm_t, hil_state) }, \
          } \
 }
 #endif
@@ -98,10 +122,18 @@ typedef struct __mavlink_payload_stats_tm_t {
  * @param min_pressure [Pa] Apogee pressure - Digital barometer
  * @param cpu_load  CPU load in percentage
  * @param free_heap  Amount of available heap in memory
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param log_good  0 if log failed, 1 otherwise
+ * @param main_board_state  Main board fmm state
+ * @param motor_board_state  Motor board fmm state
+ * @param main_can_status  Main CAN status
+ * @param motor_can_status  Motor CAN status
+ * @param rig_can_status  RIG CAN status
+ * @param hil_state  1 if the board is currently in HIL mode
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap)
+                               uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap, int16_t log_number, int32_t log_good, uint8_t main_board_state, uint8_t motor_board_state, uint8_t main_can_status, uint8_t motor_can_status, uint8_t rig_can_status, uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
@@ -120,6 +152,14 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint
     _mav_put_float(buf, 64, min_pressure);
     _mav_put_float(buf, 68, cpu_load);
     _mav_put_uint32_t(buf, 72, free_heap);
+    _mav_put_int32_t(buf, 76, log_good);
+    _mav_put_int16_t(buf, 80, log_number);
+    _mav_put_uint8_t(buf, 82, main_board_state);
+    _mav_put_uint8_t(buf, 83, motor_board_state);
+    _mav_put_uint8_t(buf, 84, main_can_status);
+    _mav_put_uint8_t(buf, 85, motor_can_status);
+    _mav_put_uint8_t(buf, 86, rig_can_status);
+    _mav_put_uint8_t(buf, 87, hil_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
 #else
@@ -139,6 +179,14 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint
     packet.min_pressure = min_pressure;
     packet.cpu_load = cpu_load;
     packet.free_heap = free_heap;
+    packet.log_good = log_good;
+    packet.log_number = log_number;
+    packet.main_board_state = main_board_state;
+    packet.motor_board_state = motor_board_state;
+    packet.main_can_status = main_can_status;
+    packet.motor_can_status = motor_can_status;
+    packet.rig_can_status = rig_can_status;
+    packet.hil_state = hil_state;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
 #endif
@@ -168,11 +216,19 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint
  * @param min_pressure [Pa] Apogee pressure - Digital barometer
  * @param cpu_load  CPU load in percentage
  * @param free_heap  Amount of available heap in memory
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param log_good  0 if log failed, 1 otherwise
+ * @param main_board_state  Main board fmm state
+ * @param motor_board_state  Motor board fmm state
+ * @param main_can_status  Main CAN status
+ * @param motor_can_status  Motor CAN status
+ * @param rig_can_status  RIG CAN status
+ * @param hil_state  1 if the board is currently in HIL mode
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_payload_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t dpl_ts,float dpl_max_acc,uint64_t max_z_speed_ts,float max_z_speed,float max_airspeed_pitot,float max_speed_altitude,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float apogee_alt,float min_pressure,float cpu_load,uint32_t free_heap)
+                                   uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t dpl_ts,float dpl_max_acc,uint64_t max_z_speed_ts,float max_z_speed,float max_airspeed_pitot,float max_speed_altitude,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float apogee_alt,float min_pressure,float cpu_load,uint32_t free_heap,int16_t log_number,int32_t log_good,uint8_t main_board_state,uint8_t motor_board_state,uint8_t main_can_status,uint8_t motor_can_status,uint8_t rig_can_status,uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
@@ -191,6 +247,14 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack_chan(uint8_t system_id,
     _mav_put_float(buf, 64, min_pressure);
     _mav_put_float(buf, 68, cpu_load);
     _mav_put_uint32_t(buf, 72, free_heap);
+    _mav_put_int32_t(buf, 76, log_good);
+    _mav_put_int16_t(buf, 80, log_number);
+    _mav_put_uint8_t(buf, 82, main_board_state);
+    _mav_put_uint8_t(buf, 83, motor_board_state);
+    _mav_put_uint8_t(buf, 84, main_can_status);
+    _mav_put_uint8_t(buf, 85, motor_can_status);
+    _mav_put_uint8_t(buf, 86, rig_can_status);
+    _mav_put_uint8_t(buf, 87, hil_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
 #else
@@ -210,6 +274,14 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack_chan(uint8_t system_id,
     packet.min_pressure = min_pressure;
     packet.cpu_load = cpu_load;
     packet.free_heap = free_heap;
+    packet.log_good = log_good;
+    packet.log_number = log_number;
+    packet.main_board_state = main_board_state;
+    packet.motor_board_state = motor_board_state;
+    packet.main_can_status = main_can_status;
+    packet.motor_can_status = motor_can_status;
+    packet.rig_can_status = rig_can_status;
+    packet.hil_state = hil_state;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
 #endif
@@ -228,7 +300,7 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack_chan(uint8_t system_id,
  */
 static inline uint16_t mavlink_msg_payload_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_payload_stats_tm_t* payload_stats_tm)
 {
-    return mavlink_msg_payload_stats_tm_pack(system_id, component_id, msg, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap);
+    return mavlink_msg_payload_stats_tm_pack(system_id, component_id, msg, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap, payload_stats_tm->log_number, payload_stats_tm->log_good, payload_stats_tm->main_board_state, payload_stats_tm->motor_board_state, payload_stats_tm->main_can_status, payload_stats_tm->motor_can_status, payload_stats_tm->rig_can_status, payload_stats_tm->hil_state);
 }
 
 /**
@@ -242,7 +314,7 @@ static inline uint16_t mavlink_msg_payload_stats_tm_encode(uint8_t system_id, ui
  */
 static inline uint16_t mavlink_msg_payload_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_payload_stats_tm_t* payload_stats_tm)
 {
-    return mavlink_msg_payload_stats_tm_pack_chan(system_id, component_id, chan, msg, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap);
+    return mavlink_msg_payload_stats_tm_pack_chan(system_id, component_id, chan, msg, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap, payload_stats_tm->log_number, payload_stats_tm->log_good, payload_stats_tm->main_board_state, payload_stats_tm->motor_board_state, payload_stats_tm->main_can_status, payload_stats_tm->motor_can_status, payload_stats_tm->rig_can_status, payload_stats_tm->hil_state);
 }
 
 /**
@@ -264,10 +336,18 @@ static inline uint16_t mavlink_msg_payload_stats_tm_encode_chan(uint8_t system_i
  * @param min_pressure [Pa] Apogee pressure - Digital barometer
  * @param cpu_load  CPU load in percentage
  * @param free_heap  Amount of available heap in memory
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param log_good  0 if log failed, 1 otherwise
+ * @param main_board_state  Main board fmm state
+ * @param motor_board_state  Motor board fmm state
+ * @param main_can_status  Main CAN status
+ * @param motor_can_status  Motor CAN status
+ * @param rig_can_status  RIG CAN status
+ * @param hil_state  1 if the board is currently in HIL mode
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap)
+static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap, int16_t log_number, int32_t log_good, uint8_t main_board_state, uint8_t motor_board_state, uint8_t main_can_status, uint8_t motor_can_status, uint8_t rig_can_status, uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
@@ -286,6 +366,14 @@ static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uin
     _mav_put_float(buf, 64, min_pressure);
     _mav_put_float(buf, 68, cpu_load);
     _mav_put_uint32_t(buf, 72, free_heap);
+    _mav_put_int32_t(buf, 76, log_good);
+    _mav_put_int16_t(buf, 80, log_number);
+    _mav_put_uint8_t(buf, 82, main_board_state);
+    _mav_put_uint8_t(buf, 83, motor_board_state);
+    _mav_put_uint8_t(buf, 84, main_can_status);
+    _mav_put_uint8_t(buf, 85, motor_can_status);
+    _mav_put_uint8_t(buf, 86, rig_can_status);
+    _mav_put_uint8_t(buf, 87, hil_state);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
 #else
@@ -305,6 +393,14 @@ static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uin
     packet.min_pressure = min_pressure;
     packet.cpu_load = cpu_load;
     packet.free_heap = free_heap;
+    packet.log_good = log_good;
+    packet.log_number = log_number;
+    packet.main_board_state = main_board_state;
+    packet.motor_board_state = motor_board_state;
+    packet.main_can_status = main_can_status;
+    packet.motor_can_status = motor_can_status;
+    packet.rig_can_status = rig_can_status;
+    packet.hil_state = hil_state;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
 #endif
@@ -318,7 +414,7 @@ static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uin
 static inline void mavlink_msg_payload_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_payload_stats_tm_t* payload_stats_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_payload_stats_tm_send(chan, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap);
+    mavlink_msg_payload_stats_tm_send(chan, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap, payload_stats_tm->log_number, payload_stats_tm->log_good, payload_stats_tm->main_board_state, payload_stats_tm->motor_board_state, payload_stats_tm->main_can_status, payload_stats_tm->motor_can_status, payload_stats_tm->rig_can_status, payload_stats_tm->hil_state);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, (const char *)payload_stats_tm, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
 #endif
@@ -332,7 +428,7 @@ static inline void mavlink_msg_payload_stats_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_payload_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap)
+static inline void mavlink_msg_payload_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap, int16_t log_number, int32_t log_good, uint8_t main_board_state, uint8_t motor_board_state, uint8_t main_can_status, uint8_t motor_can_status, uint8_t rig_can_status, uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -351,6 +447,14 @@ static inline void mavlink_msg_payload_stats_tm_send_buf(mavlink_message_t *msgb
     _mav_put_float(buf, 64, min_pressure);
     _mav_put_float(buf, 68, cpu_load);
     _mav_put_uint32_t(buf, 72, free_heap);
+    _mav_put_int32_t(buf, 76, log_good);
+    _mav_put_int16_t(buf, 80, log_number);
+    _mav_put_uint8_t(buf, 82, main_board_state);
+    _mav_put_uint8_t(buf, 83, motor_board_state);
+    _mav_put_uint8_t(buf, 84, main_can_status);
+    _mav_put_uint8_t(buf, 85, motor_can_status);
+    _mav_put_uint8_t(buf, 86, rig_can_status);
+    _mav_put_uint8_t(buf, 87, hil_state);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
 #else
@@ -370,6 +474,14 @@ static inline void mavlink_msg_payload_stats_tm_send_buf(mavlink_message_t *msgb
     packet->min_pressure = min_pressure;
     packet->cpu_load = cpu_load;
     packet->free_heap = free_heap;
+    packet->log_good = log_good;
+    packet->log_number = log_number;
+    packet->main_board_state = main_board_state;
+    packet->motor_board_state = motor_board_state;
+    packet->main_can_status = main_can_status;
+    packet->motor_can_status = motor_can_status;
+    packet->rig_can_status = rig_can_status;
+    packet->hil_state = hil_state;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
 #endif
@@ -531,6 +643,86 @@ static inline uint32_t mavlink_msg_payload_stats_tm_get_free_heap(const mavlink_
     return _MAV_RETURN_uint32_t(msg,  72);
 }
 
+/**
+ * @brief Get field log_number from payload_stats_tm message
+ *
+ * @return  Currently active log file, -1 if the logger is inactive
+ */
+static inline int16_t mavlink_msg_payload_stats_tm_get_log_number(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  80);
+}
+
+/**
+ * @brief Get field log_good from payload_stats_tm message
+ *
+ * @return  0 if log failed, 1 otherwise
+ */
+static inline int32_t mavlink_msg_payload_stats_tm_get_log_good(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  76);
+}
+
+/**
+ * @brief Get field main_board_state from payload_stats_tm message
+ *
+ * @return  Main board fmm state
+ */
+static inline uint8_t mavlink_msg_payload_stats_tm_get_main_board_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  82);
+}
+
+/**
+ * @brief Get field motor_board_state from payload_stats_tm message
+ *
+ * @return  Motor board fmm state
+ */
+static inline uint8_t mavlink_msg_payload_stats_tm_get_motor_board_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  83);
+}
+
+/**
+ * @brief Get field main_can_status from payload_stats_tm message
+ *
+ * @return  Main CAN status
+ */
+static inline uint8_t mavlink_msg_payload_stats_tm_get_main_can_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  84);
+}
+
+/**
+ * @brief Get field motor_can_status from payload_stats_tm message
+ *
+ * @return  Motor CAN status
+ */
+static inline uint8_t mavlink_msg_payload_stats_tm_get_motor_can_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  85);
+}
+
+/**
+ * @brief Get field rig_can_status from payload_stats_tm message
+ *
+ * @return  RIG CAN status
+ */
+static inline uint8_t mavlink_msg_payload_stats_tm_get_rig_can_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  86);
+}
+
+/**
+ * @brief Get field hil_state from payload_stats_tm message
+ *
+ * @return  1 if the board is currently in HIL mode
+ */
+static inline uint8_t mavlink_msg_payload_stats_tm_get_hil_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  87);
+}
+
 /**
  * @brief Decode a payload_stats_tm message into a struct
  *
@@ -555,6 +747,14 @@ static inline void mavlink_msg_payload_stats_tm_decode(const mavlink_message_t*
     payload_stats_tm->min_pressure = mavlink_msg_payload_stats_tm_get_min_pressure(msg);
     payload_stats_tm->cpu_load = mavlink_msg_payload_stats_tm_get_cpu_load(msg);
     payload_stats_tm->free_heap = mavlink_msg_payload_stats_tm_get_free_heap(msg);
+    payload_stats_tm->log_good = mavlink_msg_payload_stats_tm_get_log_good(msg);
+    payload_stats_tm->log_number = mavlink_msg_payload_stats_tm_get_log_number(msg);
+    payload_stats_tm->main_board_state = mavlink_msg_payload_stats_tm_get_main_board_state(msg);
+    payload_stats_tm->motor_board_state = mavlink_msg_payload_stats_tm_get_motor_board_state(msg);
+    payload_stats_tm->main_can_status = mavlink_msg_payload_stats_tm_get_main_can_status(msg);
+    payload_stats_tm->motor_can_status = mavlink_msg_payload_stats_tm_get_motor_can_status(msg);
+    payload_stats_tm->rig_can_status = mavlink_msg_payload_stats_tm_get_rig_can_status(msg);
+    payload_stats_tm->hil_state = mavlink_msg_payload_stats_tm_get_hil_state(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN;
         memset(payload_stats_tm, 0, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_pin_tm.h b/mavlink_lib/lyra/mavlink_msg_pin_tm.h
index 80cc7d6547bd54d6257b5450532274f2c13126ac..7664139b91883710113db1c6e2f79d879b1634c8 100644
--- a/mavlink_lib/lyra/mavlink_msg_pin_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_pin_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE PIN_TM PACKING
 
-#define MAVLINK_MSG_ID_PIN_TM 113
+#define MAVLINK_MSG_ID_PIN_TM 114
 
 
 typedef struct __mavlink_pin_tm_t {
@@ -14,17 +14,17 @@ typedef struct __mavlink_pin_tm_t {
 
 #define MAVLINK_MSG_ID_PIN_TM_LEN 19
 #define MAVLINK_MSG_ID_PIN_TM_MIN_LEN 19
-#define MAVLINK_MSG_ID_113_LEN 19
-#define MAVLINK_MSG_ID_113_MIN_LEN 19
+#define MAVLINK_MSG_ID_114_LEN 19
+#define MAVLINK_MSG_ID_114_MIN_LEN 19
 
 #define MAVLINK_MSG_ID_PIN_TM_CRC 255
-#define MAVLINK_MSG_ID_113_CRC 255
+#define MAVLINK_MSG_ID_114_CRC 255
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_PIN_TM { \
-    113, \
+    114, \
     "PIN_TM", \
     5, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pin_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_pressure_tm.h b/mavlink_lib/lyra/mavlink_msg_pressure_tm.h
index 8291d6e36b4c63ac30cc308ca496ad3c1d1ad4a6..11381c5195df40006134a28fbeb17c224bd760ef 100644
--- a/mavlink_lib/lyra/mavlink_msg_pressure_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_pressure_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE PRESSURE_TM PACKING
 
-#define MAVLINK_MSG_ID_PRESSURE_TM 104
+#define MAVLINK_MSG_ID_PRESSURE_TM 105
 
 
 typedef struct __mavlink_pressure_tm_t {
@@ -12,17 +12,17 @@ typedef struct __mavlink_pressure_tm_t {
 
 #define MAVLINK_MSG_ID_PRESSURE_TM_LEN 32
 #define MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_104_LEN 32
-#define MAVLINK_MSG_ID_104_MIN_LEN 32
+#define MAVLINK_MSG_ID_105_LEN 32
+#define MAVLINK_MSG_ID_105_MIN_LEN 32
 
 #define MAVLINK_MSG_ID_PRESSURE_TM_CRC 87
-#define MAVLINK_MSG_ID_104_CRC 87
+#define MAVLINK_MSG_ID_105_CRC 87
 
 #define MAVLINK_MSG_PRESSURE_TM_FIELD_SENSOR_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_PRESSURE_TM { \
-    104, \
+    105, \
     "PRESSURE_TM", \
     3, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pressure_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_raw_event_tc.h b/mavlink_lib/lyra/mavlink_msg_raw_event_tc.h
index fe6d60a1b38e429fc0f0049aa21234613d3c8e99..f08048e75040f7d058e4e538f4f9763b08daf7e3 100644
--- a/mavlink_lib/lyra/mavlink_msg_raw_event_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_raw_event_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE RAW_EVENT_TC PACKING
 
-#define MAVLINK_MSG_ID_RAW_EVENT_TC 13
+#define MAVLINK_MSG_ID_RAW_EVENT_TC 14
 
 
 typedef struct __mavlink_raw_event_tc_t {
@@ -11,17 +11,17 @@ typedef struct __mavlink_raw_event_tc_t {
 
 #define MAVLINK_MSG_ID_RAW_EVENT_TC_LEN 2
 #define MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN 2
-#define MAVLINK_MSG_ID_13_LEN 2
-#define MAVLINK_MSG_ID_13_MIN_LEN 2
+#define MAVLINK_MSG_ID_14_LEN 2
+#define MAVLINK_MSG_ID_14_MIN_LEN 2
 
 #define MAVLINK_MSG_ID_RAW_EVENT_TC_CRC 218
-#define MAVLINK_MSG_ID_13_CRC 218
+#define MAVLINK_MSG_ID_14_CRC 218
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
-    13, \
+    14, \
     "RAW_EVENT_TC", \
     2, \
     {  { "topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, topic_id) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_receiver_tm.h b/mavlink_lib/lyra/mavlink_msg_receiver_tm.h
deleted file mode 100644
index d87647ee1d1ad1a8b59605721d6fca6469887093..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_receiver_tm.h
+++ /dev/null
@@ -1,688 +0,0 @@
-#pragma once
-// MESSAGE RECEIVER_TM PACKING
-
-#define MAVLINK_MSG_ID_RECEIVER_TM 150
-
-
-typedef struct __mavlink_receiver_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- float main_rx_rssi; /*< [dBm] Receive RSSI*/
- float main_rx_fei; /*< [Hz] Receive frequency error index*/
- float payload_rx_rssi; /*< [dBm] Receive RSSI*/
- float payload_rx_fei; /*< [Hz] Receive frequency error index*/
- float battery_voltage; /*< [V] Battery voltage*/
- uint16_t main_packet_tx_error_count; /*<  Number of errors during send*/
- uint16_t main_tx_bitrate; /*< [b/s] Send bitrate*/
- uint16_t main_packet_rx_success_count; /*<  Number of succesfull received mavlink packets*/
- uint16_t main_packet_rx_drop_count; /*<  Number of dropped mavlink packets*/
- uint16_t main_rx_bitrate; /*< [b/s] Receive bitrate*/
- uint16_t payload_packet_tx_error_count; /*<  Number of errors during send*/
- uint16_t payload_tx_bitrate; /*< [b/s] Send bitrate*/
- uint16_t payload_packet_rx_success_count; /*<  Number of succesfull received mavlink packets*/
- uint16_t payload_packet_rx_drop_count; /*<  Number of dropped mavlink packets*/
- uint16_t payload_rx_bitrate; /*< [b/s] Receive bitrate*/
- uint8_t main_radio_present; /*<  Boolean indicating the presence of the main radio*/
- uint8_t payload_radio_present; /*<  Boolean indicating the presence of the payload radio*/
- uint8_t ethernet_present; /*<  Boolean indicating the presence of the ethernet module*/
- uint8_t ethernet_status; /*<  Status flag indicating the status of the ethernet PHY*/
-} mavlink_receiver_tm_t;
-
-#define MAVLINK_MSG_ID_RECEIVER_TM_LEN 52
-#define MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN 52
-#define MAVLINK_MSG_ID_150_LEN 52
-#define MAVLINK_MSG_ID_150_MIN_LEN 52
-
-#define MAVLINK_MSG_ID_RECEIVER_TM_CRC 117
-#define MAVLINK_MSG_ID_150_CRC 117
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RECEIVER_TM { \
-    150, \
-    "RECEIVER_TM", \
-    20, \
-    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_receiver_tm_t, timestamp) }, \
-         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_receiver_tm_t, main_radio_present) }, \
-         { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_receiver_tm_t, main_packet_tx_error_count) }, \
-         { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_receiver_tm_t, main_tx_bitrate) }, \
-         { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_receiver_tm_t, main_packet_rx_success_count) }, \
-         { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_receiver_tm_t, main_packet_rx_drop_count) }, \
-         { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_receiver_tm_t, main_rx_bitrate) }, \
-         { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_receiver_tm_t, main_rx_rssi) }, \
-         { "main_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_receiver_tm_t, main_rx_fei) }, \
-         { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_receiver_tm_t, payload_radio_present) }, \
-         { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_receiver_tm_t, payload_packet_tx_error_count) }, \
-         { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_receiver_tm_t, payload_tx_bitrate) }, \
-         { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_receiver_tm_t, payload_packet_rx_success_count) }, \
-         { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_receiver_tm_t, payload_packet_rx_drop_count) }, \
-         { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_receiver_tm_t, payload_rx_bitrate) }, \
-         { "payload_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_receiver_tm_t, payload_rx_rssi) }, \
-         { "payload_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_receiver_tm_t, payload_rx_fei) }, \
-         { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_receiver_tm_t, ethernet_present) }, \
-         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_receiver_tm_t, ethernet_status) }, \
-         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_receiver_tm_t, battery_voltage) }, \
-         } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RECEIVER_TM { \
-    "RECEIVER_TM", \
-    20, \
-    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_receiver_tm_t, timestamp) }, \
-         { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_receiver_tm_t, main_radio_present) }, \
-         { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_receiver_tm_t, main_packet_tx_error_count) }, \
-         { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_receiver_tm_t, main_tx_bitrate) }, \
-         { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_receiver_tm_t, main_packet_rx_success_count) }, \
-         { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_receiver_tm_t, main_packet_rx_drop_count) }, \
-         { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_receiver_tm_t, main_rx_bitrate) }, \
-         { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_receiver_tm_t, main_rx_rssi) }, \
-         { "main_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_receiver_tm_t, main_rx_fei) }, \
-         { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_receiver_tm_t, payload_radio_present) }, \
-         { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_receiver_tm_t, payload_packet_tx_error_count) }, \
-         { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_receiver_tm_t, payload_tx_bitrate) }, \
-         { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_receiver_tm_t, payload_packet_rx_success_count) }, \
-         { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_receiver_tm_t, payload_packet_rx_drop_count) }, \
-         { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_receiver_tm_t, payload_rx_bitrate) }, \
-         { "payload_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_receiver_tm_t, payload_rx_rssi) }, \
-         { "payload_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_receiver_tm_t, payload_rx_fei) }, \
-         { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_receiver_tm_t, ethernet_present) }, \
-         { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_receiver_tm_t, ethernet_status) }, \
-         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_receiver_tm_t, battery_voltage) }, \
-         } \
-}
-#endif
-
-/**
- * @brief Pack a receiver_tm message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- *
- * @param timestamp [us] Timestamp
- * @param main_radio_present  Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count  Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count  Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count  Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param main_rx_fei [Hz] Receive frequency error index
- * @param payload_radio_present  Boolean indicating the presence of the payload radio
- * @param payload_packet_tx_error_count  Number of errors during send
- * @param payload_tx_bitrate [b/s] Send bitrate
- * @param payload_packet_rx_success_count  Number of succesfull received mavlink packets
- * @param payload_packet_rx_drop_count  Number of dropped mavlink packets
- * @param payload_rx_bitrate [b/s] Receive bitrate
- * @param payload_rx_rssi [dBm] Receive RSSI
- * @param payload_rx_fei [Hz] Receive frequency error index
- * @param ethernet_present  Boolean indicating the presence of the ethernet module
- * @param ethernet_status  Status flag indicating the status of the ethernet PHY
- * @param battery_voltage [V] Battery voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_receiver_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
-    _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_float(buf, 8, main_rx_rssi);
-    _mav_put_float(buf, 12, main_rx_fei);
-    _mav_put_float(buf, 16, payload_rx_rssi);
-    _mav_put_float(buf, 20, payload_rx_fei);
-    _mav_put_float(buf, 24, battery_voltage);
-    _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 30, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 36, main_rx_bitrate);
-    _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
-    _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
-    _mav_put_uint8_t(buf, 48, main_radio_present);
-    _mav_put_uint8_t(buf, 49, payload_radio_present);
-    _mav_put_uint8_t(buf, 50, ethernet_present);
-    _mav_put_uint8_t(buf, 51, ethernet_status);
-
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#else
-    mavlink_receiver_tm_t packet;
-    packet.timestamp = timestamp;
-    packet.main_rx_rssi = main_rx_rssi;
-    packet.main_rx_fei = main_rx_fei;
-    packet.payload_rx_rssi = payload_rx_rssi;
-    packet.payload_rx_fei = payload_rx_fei;
-    packet.battery_voltage = battery_voltage;
-    packet.main_packet_tx_error_count = main_packet_tx_error_count;
-    packet.main_tx_bitrate = main_tx_bitrate;
-    packet.main_packet_rx_success_count = main_packet_rx_success_count;
-    packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
-    packet.main_rx_bitrate = main_rx_bitrate;
-    packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
-    packet.payload_tx_bitrate = payload_tx_bitrate;
-    packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
-    packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
-    packet.payload_rx_bitrate = payload_rx_bitrate;
-    packet.main_radio_present = main_radio_present;
-    packet.payload_radio_present = payload_radio_present;
-    packet.ethernet_present = ethernet_present;
-    packet.ethernet_status = ethernet_status;
-
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#endif
-
-    msg->msgid = MAVLINK_MSG_ID_RECEIVER_TM;
-    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-}
-
-/**
- * @brief Pack a receiver_tm message on a channel
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message will be sent over
- * @param msg The MAVLink message to compress the data into
- * @param timestamp [us] Timestamp
- * @param main_radio_present  Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count  Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count  Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count  Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param main_rx_fei [Hz] Receive frequency error index
- * @param payload_radio_present  Boolean indicating the presence of the payload radio
- * @param payload_packet_tx_error_count  Number of errors during send
- * @param payload_tx_bitrate [b/s] Send bitrate
- * @param payload_packet_rx_success_count  Number of succesfull received mavlink packets
- * @param payload_packet_rx_drop_count  Number of dropped mavlink packets
- * @param payload_rx_bitrate [b/s] Receive bitrate
- * @param payload_rx_rssi [dBm] Receive RSSI
- * @param payload_rx_fei [Hz] Receive frequency error index
- * @param ethernet_present  Boolean indicating the presence of the ethernet module
- * @param ethernet_status  Status flag indicating the status of the ethernet PHY
- * @param battery_voltage [V] Battery voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_receiver_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
-                               mavlink_message_t* msg,
-                                   uint64_t timestamp,uint8_t main_radio_present,uint16_t main_packet_tx_error_count,uint16_t main_tx_bitrate,uint16_t main_packet_rx_success_count,uint16_t main_packet_rx_drop_count,uint16_t main_rx_bitrate,float main_rx_rssi,float main_rx_fei,uint8_t payload_radio_present,uint16_t payload_packet_tx_error_count,uint16_t payload_tx_bitrate,uint16_t payload_packet_rx_success_count,uint16_t payload_packet_rx_drop_count,uint16_t payload_rx_bitrate,float payload_rx_rssi,float payload_rx_fei,uint8_t ethernet_present,uint8_t ethernet_status,float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
-    _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_float(buf, 8, main_rx_rssi);
-    _mav_put_float(buf, 12, main_rx_fei);
-    _mav_put_float(buf, 16, payload_rx_rssi);
-    _mav_put_float(buf, 20, payload_rx_fei);
-    _mav_put_float(buf, 24, battery_voltage);
-    _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 30, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 36, main_rx_bitrate);
-    _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
-    _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
-    _mav_put_uint8_t(buf, 48, main_radio_present);
-    _mav_put_uint8_t(buf, 49, payload_radio_present);
-    _mav_put_uint8_t(buf, 50, ethernet_present);
-    _mav_put_uint8_t(buf, 51, ethernet_status);
-
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#else
-    mavlink_receiver_tm_t packet;
-    packet.timestamp = timestamp;
-    packet.main_rx_rssi = main_rx_rssi;
-    packet.main_rx_fei = main_rx_fei;
-    packet.payload_rx_rssi = payload_rx_rssi;
-    packet.payload_rx_fei = payload_rx_fei;
-    packet.battery_voltage = battery_voltage;
-    packet.main_packet_tx_error_count = main_packet_tx_error_count;
-    packet.main_tx_bitrate = main_tx_bitrate;
-    packet.main_packet_rx_success_count = main_packet_rx_success_count;
-    packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
-    packet.main_rx_bitrate = main_rx_bitrate;
-    packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
-    packet.payload_tx_bitrate = payload_tx_bitrate;
-    packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
-    packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
-    packet.payload_rx_bitrate = payload_rx_bitrate;
-    packet.main_radio_present = main_radio_present;
-    packet.payload_radio_present = payload_radio_present;
-    packet.ethernet_present = ethernet_present;
-    packet.ethernet_status = ethernet_status;
-
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#endif
-
-    msg->msgid = MAVLINK_MSG_ID_RECEIVER_TM;
-    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-}
-
-/**
- * @brief Encode a receiver_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 receiver_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_receiver_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_receiver_tm_t* receiver_tm)
-{
-    return mavlink_msg_receiver_tm_pack(system_id, component_id, msg, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei, receiver_tm->ethernet_present, receiver_tm->ethernet_status, receiver_tm->battery_voltage);
-}
-
-/**
- * @brief Encode a receiver_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 receiver_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_receiver_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_receiver_tm_t* receiver_tm)
-{
-    return mavlink_msg_receiver_tm_pack_chan(system_id, component_id, chan, msg, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei, receiver_tm->ethernet_present, receiver_tm->ethernet_status, receiver_tm->battery_voltage);
-}
-
-/**
- * @brief Send a receiver_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param main_radio_present  Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count  Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count  Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count  Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param main_rx_fei [Hz] Receive frequency error index
- * @param payload_radio_present  Boolean indicating the presence of the payload radio
- * @param payload_packet_tx_error_count  Number of errors during send
- * @param payload_tx_bitrate [b/s] Send bitrate
- * @param payload_packet_rx_success_count  Number of succesfull received mavlink packets
- * @param payload_packet_rx_drop_count  Number of dropped mavlink packets
- * @param payload_rx_bitrate [b/s] Receive bitrate
- * @param payload_rx_rssi [dBm] Receive RSSI
- * @param payload_rx_fei [Hz] Receive frequency error index
- * @param ethernet_present  Boolean indicating the presence of the ethernet module
- * @param ethernet_status  Status flag indicating the status of the ethernet PHY
- * @param battery_voltage [V] Battery voltage
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_receiver_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
-    _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_float(buf, 8, main_rx_rssi);
-    _mav_put_float(buf, 12, main_rx_fei);
-    _mav_put_float(buf, 16, payload_rx_rssi);
-    _mav_put_float(buf, 20, payload_rx_fei);
-    _mav_put_float(buf, 24, battery_voltage);
-    _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 30, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 36, main_rx_bitrate);
-    _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
-    _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
-    _mav_put_uint8_t(buf, 48, main_radio_present);
-    _mav_put_uint8_t(buf, 49, payload_radio_present);
-    _mav_put_uint8_t(buf, 50, ethernet_present);
-    _mav_put_uint8_t(buf, 51, ethernet_status);
-
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, buf, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#else
-    mavlink_receiver_tm_t packet;
-    packet.timestamp = timestamp;
-    packet.main_rx_rssi = main_rx_rssi;
-    packet.main_rx_fei = main_rx_fei;
-    packet.payload_rx_rssi = payload_rx_rssi;
-    packet.payload_rx_fei = payload_rx_fei;
-    packet.battery_voltage = battery_voltage;
-    packet.main_packet_tx_error_count = main_packet_tx_error_count;
-    packet.main_tx_bitrate = main_tx_bitrate;
-    packet.main_packet_rx_success_count = main_packet_rx_success_count;
-    packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
-    packet.main_rx_bitrate = main_rx_bitrate;
-    packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
-    packet.payload_tx_bitrate = payload_tx_bitrate;
-    packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
-    packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
-    packet.payload_rx_bitrate = payload_rx_bitrate;
-    packet.main_radio_present = main_radio_present;
-    packet.payload_radio_present = payload_radio_present;
-    packet.ethernet_present = ethernet_present;
-    packet.ethernet_status = ethernet_status;
-
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)&packet, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a receiver_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_receiver_tm_send_struct(mavlink_channel_t chan, const mavlink_receiver_tm_t* receiver_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_receiver_tm_send(chan, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei, receiver_tm->ethernet_present, receiver_tm->ethernet_status, receiver_tm->battery_voltage);
-#else
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)receiver_tm, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RECEIVER_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_receiver_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char *buf = (char *)msgbuf;
-    _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_float(buf, 8, main_rx_rssi);
-    _mav_put_float(buf, 12, main_rx_fei);
-    _mav_put_float(buf, 16, payload_rx_rssi);
-    _mav_put_float(buf, 20, payload_rx_fei);
-    _mav_put_float(buf, 24, battery_voltage);
-    _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 30, main_tx_bitrate);
-    _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 36, main_rx_bitrate);
-    _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
-    _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
-    _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
-    _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
-    _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
-    _mav_put_uint8_t(buf, 48, main_radio_present);
-    _mav_put_uint8_t(buf, 49, payload_radio_present);
-    _mav_put_uint8_t(buf, 50, ethernet_present);
-    _mav_put_uint8_t(buf, 51, ethernet_status);
-
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, buf, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#else
-    mavlink_receiver_tm_t *packet = (mavlink_receiver_tm_t *)msgbuf;
-    packet->timestamp = timestamp;
-    packet->main_rx_rssi = main_rx_rssi;
-    packet->main_rx_fei = main_rx_fei;
-    packet->payload_rx_rssi = payload_rx_rssi;
-    packet->payload_rx_fei = payload_rx_fei;
-    packet->battery_voltage = battery_voltage;
-    packet->main_packet_tx_error_count = main_packet_tx_error_count;
-    packet->main_tx_bitrate = main_tx_bitrate;
-    packet->main_packet_rx_success_count = main_packet_rx_success_count;
-    packet->main_packet_rx_drop_count = main_packet_rx_drop_count;
-    packet->main_rx_bitrate = main_rx_bitrate;
-    packet->payload_packet_tx_error_count = payload_packet_tx_error_count;
-    packet->payload_tx_bitrate = payload_tx_bitrate;
-    packet->payload_packet_rx_success_count = payload_packet_rx_success_count;
-    packet->payload_packet_rx_drop_count = payload_packet_rx_drop_count;
-    packet->payload_rx_bitrate = payload_rx_bitrate;
-    packet->main_radio_present = main_radio_present;
-    packet->payload_radio_present = payload_radio_present;
-    packet->ethernet_present = ethernet_present;
-    packet->ethernet_status = ethernet_status;
-
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)packet, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RECEIVER_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from receiver_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_receiver_tm_get_timestamp(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint64_t(msg,  0);
-}
-
-/**
- * @brief Get field main_radio_present from receiver_tm message
- *
- * @return  Boolean indicating the presence of the main radio
- */
-static inline uint8_t mavlink_msg_receiver_tm_get_main_radio_present(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  48);
-}
-
-/**
- * @brief Get field main_packet_tx_error_count from receiver_tm message
- *
- * @return  Number of errors during send
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_tx_error_count(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  28);
-}
-
-/**
- * @brief Get field main_tx_bitrate from receiver_tm message
- *
- * @return [b/s] Send bitrate
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_tx_bitrate(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  30);
-}
-
-/**
- * @brief Get field main_packet_rx_success_count from receiver_tm message
- *
- * @return  Number of succesfull received mavlink packets
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_rx_success_count(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  32);
-}
-
-/**
- * @brief Get field main_packet_rx_drop_count from receiver_tm message
- *
- * @return  Number of dropped mavlink packets
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_rx_drop_count(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  34);
-}
-
-/**
- * @brief Get field main_rx_bitrate from receiver_tm message
- *
- * @return [b/s] Receive bitrate
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_rx_bitrate(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  36);
-}
-
-/**
- * @brief Get field main_rx_rssi from receiver_tm message
- *
- * @return [dBm] Receive RSSI
- */
-static inline float mavlink_msg_receiver_tm_get_main_rx_rssi(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_float(msg,  8);
-}
-
-/**
- * @brief Get field main_rx_fei from receiver_tm message
- *
- * @return [Hz] Receive frequency error index
- */
-static inline float mavlink_msg_receiver_tm_get_main_rx_fei(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_float(msg,  12);
-}
-
-/**
- * @brief Get field payload_radio_present from receiver_tm message
- *
- * @return  Boolean indicating the presence of the payload radio
- */
-static inline uint8_t mavlink_msg_receiver_tm_get_payload_radio_present(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  49);
-}
-
-/**
- * @brief Get field payload_packet_tx_error_count from receiver_tm message
- *
- * @return  Number of errors during send
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_tx_error_count(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  38);
-}
-
-/**
- * @brief Get field payload_tx_bitrate from receiver_tm message
- *
- * @return [b/s] Send bitrate
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_tx_bitrate(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  40);
-}
-
-/**
- * @brief Get field payload_packet_rx_success_count from receiver_tm message
- *
- * @return  Number of succesfull received mavlink packets
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_rx_success_count(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  42);
-}
-
-/**
- * @brief Get field payload_packet_rx_drop_count from receiver_tm message
- *
- * @return  Number of dropped mavlink packets
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_rx_drop_count(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  44);
-}
-
-/**
- * @brief Get field payload_rx_bitrate from receiver_tm message
- *
- * @return [b/s] Receive bitrate
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_rx_bitrate(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  46);
-}
-
-/**
- * @brief Get field payload_rx_rssi from receiver_tm message
- *
- * @return [dBm] Receive RSSI
- */
-static inline float mavlink_msg_receiver_tm_get_payload_rx_rssi(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_float(msg,  16);
-}
-
-/**
- * @brief Get field payload_rx_fei from receiver_tm message
- *
- * @return [Hz] Receive frequency error index
- */
-static inline float mavlink_msg_receiver_tm_get_payload_rx_fei(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_float(msg,  20);
-}
-
-/**
- * @brief Get field ethernet_present from receiver_tm message
- *
- * @return  Boolean indicating the presence of the ethernet module
- */
-static inline uint8_t mavlink_msg_receiver_tm_get_ethernet_present(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  50);
-}
-
-/**
- * @brief Get field ethernet_status from receiver_tm message
- *
- * @return  Status flag indicating the status of the ethernet PHY
- */
-static inline uint8_t mavlink_msg_receiver_tm_get_ethernet_status(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  51);
-}
-
-/**
- * @brief Get field battery_voltage from receiver_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_receiver_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_float(msg,  24);
-}
-
-/**
- * @brief Decode a receiver_tm message into a struct
- *
- * @param msg The message to decode
- * @param receiver_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_receiver_tm_decode(const mavlink_message_t* msg, mavlink_receiver_tm_t* receiver_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    receiver_tm->timestamp = mavlink_msg_receiver_tm_get_timestamp(msg);
-    receiver_tm->main_rx_rssi = mavlink_msg_receiver_tm_get_main_rx_rssi(msg);
-    receiver_tm->main_rx_fei = mavlink_msg_receiver_tm_get_main_rx_fei(msg);
-    receiver_tm->payload_rx_rssi = mavlink_msg_receiver_tm_get_payload_rx_rssi(msg);
-    receiver_tm->payload_rx_fei = mavlink_msg_receiver_tm_get_payload_rx_fei(msg);
-    receiver_tm->battery_voltage = mavlink_msg_receiver_tm_get_battery_voltage(msg);
-    receiver_tm->main_packet_tx_error_count = mavlink_msg_receiver_tm_get_main_packet_tx_error_count(msg);
-    receiver_tm->main_tx_bitrate = mavlink_msg_receiver_tm_get_main_tx_bitrate(msg);
-    receiver_tm->main_packet_rx_success_count = mavlink_msg_receiver_tm_get_main_packet_rx_success_count(msg);
-    receiver_tm->main_packet_rx_drop_count = mavlink_msg_receiver_tm_get_main_packet_rx_drop_count(msg);
-    receiver_tm->main_rx_bitrate = mavlink_msg_receiver_tm_get_main_rx_bitrate(msg);
-    receiver_tm->payload_packet_tx_error_count = mavlink_msg_receiver_tm_get_payload_packet_tx_error_count(msg);
-    receiver_tm->payload_tx_bitrate = mavlink_msg_receiver_tm_get_payload_tx_bitrate(msg);
-    receiver_tm->payload_packet_rx_success_count = mavlink_msg_receiver_tm_get_payload_packet_rx_success_count(msg);
-    receiver_tm->payload_packet_rx_drop_count = mavlink_msg_receiver_tm_get_payload_packet_rx_drop_count(msg);
-    receiver_tm->payload_rx_bitrate = mavlink_msg_receiver_tm_get_payload_rx_bitrate(msg);
-    receiver_tm->main_radio_present = mavlink_msg_receiver_tm_get_main_radio_present(msg);
-    receiver_tm->payload_radio_present = mavlink_msg_receiver_tm_get_payload_radio_present(msg);
-    receiver_tm->ethernet_present = mavlink_msg_receiver_tm_get_ethernet_present(msg);
-    receiver_tm->ethernet_status = mavlink_msg_receiver_tm_get_ethernet_status(msg);
-#else
-        uint8_t len = msg->len < MAVLINK_MSG_ID_RECEIVER_TM_LEN? msg->len : MAVLINK_MSG_ID_RECEIVER_TM_LEN;
-        memset(receiver_tm, 0, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-    memcpy(receiver_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_registry_coord_tm.h b/mavlink_lib/lyra/mavlink_msg_registry_coord_tm.h
index f539c5d07179bc151c00bc673dc658bb397f5a80..e4c2e071a0582bafdb95b0e153ad2557a44407d5 100644
--- a/mavlink_lib/lyra/mavlink_msg_registry_coord_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_registry_coord_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE REGISTRY_COORD_TM PACKING
 
-#define MAVLINK_MSG_ID_REGISTRY_COORD_TM 116
+#define MAVLINK_MSG_ID_REGISTRY_COORD_TM 117
 
 
 typedef struct __mavlink_registry_coord_tm_t {
@@ -14,17 +14,17 @@ typedef struct __mavlink_registry_coord_tm_t {
 
 #define MAVLINK_MSG_ID_REGISTRY_COORD_TM_LEN 40
 #define MAVLINK_MSG_ID_REGISTRY_COORD_TM_MIN_LEN 40
-#define MAVLINK_MSG_ID_116_LEN 40
-#define MAVLINK_MSG_ID_116_MIN_LEN 40
+#define MAVLINK_MSG_ID_117_LEN 40
+#define MAVLINK_MSG_ID_117_MIN_LEN 40
 
 #define MAVLINK_MSG_ID_REGISTRY_COORD_TM_CRC 234
-#define MAVLINK_MSG_ID_116_CRC 234
+#define MAVLINK_MSG_ID_117_CRC 234
 
 #define MAVLINK_MSG_REGISTRY_COORD_TM_FIELD_KEY_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_REGISTRY_COORD_TM { \
-    116, \
+    117, \
     "REGISTRY_COORD_TM", \
     5, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_registry_coord_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_registry_float_tm.h b/mavlink_lib/lyra/mavlink_msg_registry_float_tm.h
index 97e592634ff72dda0eb422480f6aad8b4caf4918..68fd8f76aa37571aae3d3e5a8b2d2564487cbbfc 100644
--- a/mavlink_lib/lyra/mavlink_msg_registry_float_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_registry_float_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE REGISTRY_FLOAT_TM PACKING
 
-#define MAVLINK_MSG_ID_REGISTRY_FLOAT_TM 114
+#define MAVLINK_MSG_ID_REGISTRY_FLOAT_TM 115
 
 
 typedef struct __mavlink_registry_float_tm_t {
@@ -13,17 +13,17 @@ typedef struct __mavlink_registry_float_tm_t {
 
 #define MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_LEN 36
 #define MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_MIN_LEN 36
-#define MAVLINK_MSG_ID_114_LEN 36
-#define MAVLINK_MSG_ID_114_MIN_LEN 36
+#define MAVLINK_MSG_ID_115_LEN 36
+#define MAVLINK_MSG_ID_115_MIN_LEN 36
 
 #define MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_CRC 9
-#define MAVLINK_MSG_ID_114_CRC 9
+#define MAVLINK_MSG_ID_115_CRC 9
 
 #define MAVLINK_MSG_REGISTRY_FLOAT_TM_FIELD_KEY_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_REGISTRY_FLOAT_TM { \
-    114, \
+    115, \
     "REGISTRY_FLOAT_TM", \
     4, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_registry_float_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_registry_int_tm.h b/mavlink_lib/lyra/mavlink_msg_registry_int_tm.h
index 233fd532e243b05951980dc1c9ff9bf56f7b2c23..fd0786614f86a7d02864e8204e00b766d1acb121 100644
--- a/mavlink_lib/lyra/mavlink_msg_registry_int_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_registry_int_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE REGISTRY_INT_TM PACKING
 
-#define MAVLINK_MSG_ID_REGISTRY_INT_TM 115
+#define MAVLINK_MSG_ID_REGISTRY_INT_TM 116
 
 
 typedef struct __mavlink_registry_int_tm_t {
@@ -13,17 +13,17 @@ typedef struct __mavlink_registry_int_tm_t {
 
 #define MAVLINK_MSG_ID_REGISTRY_INT_TM_LEN 36
 #define MAVLINK_MSG_ID_REGISTRY_INT_TM_MIN_LEN 36
-#define MAVLINK_MSG_ID_115_LEN 36
-#define MAVLINK_MSG_ID_115_MIN_LEN 36
+#define MAVLINK_MSG_ID_116_LEN 36
+#define MAVLINK_MSG_ID_116_MIN_LEN 36
 
 #define MAVLINK_MSG_ID_REGISTRY_INT_TM_CRC 68
-#define MAVLINK_MSG_ID_115_CRC 68
+#define MAVLINK_MSG_ID_116_CRC 68
 
 #define MAVLINK_MSG_REGISTRY_INT_TM_FIELD_KEY_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_REGISTRY_INT_TM { \
-    115, \
+    116, \
     "REGISTRY_INT_TM", \
     4, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_registry_int_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_reset_servo_tc.h b/mavlink_lib/lyra/mavlink_msg_reset_servo_tc.h
index 3194a30241ddfb4d40efc96b727240c69f4842ac..6a7c1b4e39eafbfb3c316260de23a6716df10888 100644
--- a/mavlink_lib/lyra/mavlink_msg_reset_servo_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_reset_servo_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE RESET_SERVO_TC PACKING
 
-#define MAVLINK_MSG_ID_RESET_SERVO_TC 8
+#define MAVLINK_MSG_ID_RESET_SERVO_TC 7
 
 
 typedef struct __mavlink_reset_servo_tc_t {
@@ -10,17 +10,17 @@ typedef struct __mavlink_reset_servo_tc_t {
 
 #define MAVLINK_MSG_ID_RESET_SERVO_TC_LEN 1
 #define MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_8_LEN 1
-#define MAVLINK_MSG_ID_8_MIN_LEN 1
+#define MAVLINK_MSG_ID_7_LEN 1
+#define MAVLINK_MSG_ID_7_MIN_LEN 1
 
 #define MAVLINK_MSG_ID_RESET_SERVO_TC_CRC 226
-#define MAVLINK_MSG_ID_8_CRC 226
+#define MAVLINK_MSG_ID_7_CRC 226
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_RESET_SERVO_TC { \
-    8, \
+    7, \
     "RESET_SERVO_TC", \
     1, \
     {  { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_reset_servo_tc_t, servo_id) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_rocket_flight_tm.h b/mavlink_lib/lyra/mavlink_msg_rocket_flight_tm.h
index e3949ca456e8719920b4822b1e08e708b2e51b26..5ecac66e2c29c7367704a1ab6383f88172b4f8e9 100644
--- a/mavlink_lib/lyra/mavlink_msg_rocket_flight_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_rocket_flight_tm.h
@@ -27,45 +27,42 @@ 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 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*/
- float nas_vn; /*< [m/s] Navigation system estimated north velocity*/
- float nas_ve; /*< [m/s] Navigation system estimated east velocity*/
- float nas_vd; /*< [m/s] Navigation system estimated down velocity*/
- float nas_qx; /*< [deg] Navigation system estimated attitude (qx)*/
- float nas_qy; /*< [deg] Navigation system estimated attitude (qy)*/
- float nas_qz; /*< [deg] Navigation system estimated attitude (qz)*/
- float nas_qw; /*< [deg] Navigation system estimated attitude (qw)*/
- float nas_bias_x; /*<  Navigation system gyroscope bias on x axis*/
- float nas_bias_y; /*<  Navigation system gyroscope bias on y axis*/
- float nas_bias_z; /*<  Navigation system gyroscope bias on z axis*/
- float pin_quick_connector; /*<   Quick connector detach pin */
+ float nas_n; /*< [deg] NAS estimated noth position*/
+ float nas_e; /*< [deg] NAS estimated east position*/
+ float nas_d; /*< [m] NAS estimated down position*/
+ float nas_vn; /*< [m/s] NAS estimated north velocity*/
+ float nas_ve; /*< [m/s] NAS estimated east velocity*/
+ float nas_vd; /*< [m/s] NAS estimated down velocity*/
+ float nas_qx; /*< [deg] NAS estimated attitude (qx)*/
+ float nas_qy; /*< [deg] NAS estimated attitude (qy)*/
+ float nas_qz; /*< [deg] NAS estimated attitude (qz)*/
+ float nas_qw; /*< [deg] NAS estimated attitude (qw)*/
+ float nas_bias_x; /*<  NAS gyroscope bias on x axis*/
+ float nas_bias_y; /*<  NAS gyroscope bias on y axis*/
+ float nas_bias_z; /*<  NAS gyroscope bias on z axis*/
  float battery_voltage; /*< [V] Battery voltage*/
  float cam_battery_voltage; /*< [V] Camera 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 nas_state; /*<  NAS 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)*/
  uint8_t pin_expulsion; /*<  Servo sensor status (1 = actuated, 0 = idle)*/
  uint8_t cutter_presence; /*<  Cutter presence status (1 = present, 0 = missing)*/
- int8_t logger_error; /*<  Logger error (0 = no error, -1 otherwise)*/
 } mavlink_rocket_flight_tm_t;
 
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN 176
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN 176
-#define MAVLINK_MSG_ID_208_LEN 176
-#define MAVLINK_MSG_ID_208_MIN_LEN 176
+#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN 167
+#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN 167
+#define MAVLINK_MSG_ID_208_LEN 167
+#define MAVLINK_MSG_ID_208_MIN_LEN 167
 
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC 214
-#define MAVLINK_MSG_ID_208_CRC 214
+#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC 52
+#define MAVLINK_MSG_ID_208_CRC 52
 
 
 
@@ -73,14 +70,14 @@ typedef struct __mavlink_rocket_flight_tm_t {
 #define MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM { \
     208, \
     "ROCKET_FLIGHT_TM", \
-    52, \
+    49, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \
-         { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
-         { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
-         { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
-         { "mea_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_rocket_flight_tm_t, mea_state) }, \
+         { "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) }, \
@@ -98,7 +95,7 @@ typedef struct __mavlink_rocket_flight_tm_t {
          { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \
          { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \
          { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 170, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
+         { "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) }, \
@@ -116,29 +113,26 @@ typedef struct __mavlink_rocket_flight_tm_t {
          { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
          { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
          { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
-         { "pin_quick_connector", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, pin_quick_connector) }, \
-         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 171, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
-         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 172, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
-         { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 173, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
-         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 174, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
-         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, battery_voltage) }, \
-         { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, cam_battery_voltage) }, \
-         { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_rocket_flight_tm_t, current_consumption) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 160, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
-         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 175, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
+         { "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) }, \
+         { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, cam_battery_voltage) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM { \
     "ROCKET_FLIGHT_TM", \
-    52, \
+    49, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \
-         { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
-         { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
-         { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
-         { "mea_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_rocket_flight_tm_t, mea_state) }, \
+         { "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) }, \
@@ -156,7 +150,7 @@ typedef struct __mavlink_rocket_flight_tm_t {
          { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \
          { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \
          { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 170, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
+         { "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) }, \
@@ -174,16 +168,13 @@ typedef struct __mavlink_rocket_flight_tm_t {
          { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
          { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
          { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
-         { "pin_quick_connector", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, pin_quick_connector) }, \
-         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 171, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
-         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 172, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
-         { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 173, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
-         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 174, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
-         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, battery_voltage) }, \
-         { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, cam_battery_voltage) }, \
-         { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_rocket_flight_tm_t, current_consumption) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 160, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
-         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 175, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
+         { "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) }, \
+         { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, cam_battery_voltage) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
          } \
 }
 #endif
@@ -199,7 +190,7 @@ typedef struct __mavlink_rocket_flight_tm_t {
  * @param fmm_state  Flight Mode Manager State
  * @param dpl_state  Deployment Controller State
  * @param abk_state  Airbrake FSM state
- * @param nas_state  Navigation System FSM State
+ * @param nas_state  NAS FSM State
  * @param mea_state  MEA Controller State
  * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
  * @param pressure_digi [Pa] Pressure from digital sensor
@@ -223,33 +214,30 @@ 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 nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x  Navigation system gyroscope bias on x axis
- * @param nas_bias_y  Navigation system gyroscope bias on y axis
- * @param nas_bias_z  Navigation system gyroscope bias on z axis
- * @param pin_quick_connector   Quick connector detach pin 
+ * @param nas_n [deg] NAS estimated noth position
+ * @param nas_e [deg] NAS estimated east position
+ * @param nas_d [m] NAS estimated down position
+ * @param nas_vn [m/s] NAS estimated north velocity
+ * @param nas_ve [m/s] NAS estimated east velocity
+ * @param nas_vd [m/s] NAS estimated down velocity
+ * @param nas_qx [deg] NAS estimated attitude (qx)
+ * @param nas_qy [deg] NAS estimated attitude (qy)
+ * @param nas_qz [deg] NAS estimated attitude (qz)
+ * @param nas_qw [deg] NAS estimated attitude (qw)
+ * @param nas_bias_x  NAS gyroscope bias on x axis
+ * @param nas_bias_y  NAS gyroscope bias on y axis
+ * @param nas_bias_z  NAS gyroscope bias on z axis
  * @param pin_launch  Launch pin status (1 = connected, 0 = disconnected)
  * @param pin_nosecone  Nosecone pin status (1 = connected, 0 = disconnected)
  * @param pin_expulsion  Servo sensor status (1 = actuated, 0 = idle)
  * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
  * @param battery_voltage [V] Battery voltage
  * @param cam_battery_voltage [V] Camera battery voltage
- * @param 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, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float pin_quick_connector, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
+                               uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float temperature)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
@@ -288,23 +276,20 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
     _mav_put_float(buf, 132, nas_bias_x);
     _mav_put_float(buf, 136, nas_bias_y);
     _mav_put_float(buf, 140, nas_bias_z);
-    _mav_put_float(buf, 144, pin_quick_connector);
-    _mav_put_float(buf, 148, battery_voltage);
-    _mav_put_float(buf, 152, cam_battery_voltage);
-    _mav_put_float(buf, 156, current_consumption);
-    _mav_put_float(buf, 160, temperature);
-    _mav_put_uint8_t(buf, 164, ada_state);
-    _mav_put_uint8_t(buf, 165, fmm_state);
-    _mav_put_uint8_t(buf, 166, dpl_state);
-    _mav_put_uint8_t(buf, 167, abk_state);
-    _mav_put_uint8_t(buf, 168, nas_state);
-    _mav_put_uint8_t(buf, 169, mea_state);
-    _mav_put_uint8_t(buf, 170, gps_fix);
-    _mav_put_uint8_t(buf, 171, pin_launch);
-    _mav_put_uint8_t(buf, 172, pin_nosecone);
-    _mav_put_uint8_t(buf, 173, pin_expulsion);
-    _mav_put_uint8_t(buf, 174, cutter_presence);
-    _mav_put_int8_t(buf, 175, logger_error);
+    _mav_put_float(buf, 144, battery_voltage);
+    _mav_put_float(buf, 148, cam_battery_voltage);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, ada_state);
+    _mav_put_uint8_t(buf, 157, fmm_state);
+    _mav_put_uint8_t(buf, 158, dpl_state);
+    _mav_put_uint8_t(buf, 159, abk_state);
+    _mav_put_uint8_t(buf, 160, nas_state);
+    _mav_put_uint8_t(buf, 161, mea_state);
+    _mav_put_uint8_t(buf, 162, gps_fix);
+    _mav_put_uint8_t(buf, 163, pin_launch);
+    _mav_put_uint8_t(buf, 164, pin_nosecone);
+    _mav_put_uint8_t(buf, 165, pin_expulsion);
+    _mav_put_uint8_t(buf, 166, cutter_presence);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
 #else
@@ -344,10 +329,8 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
     packet.nas_bias_x = nas_bias_x;
     packet.nas_bias_y = nas_bias_y;
     packet.nas_bias_z = nas_bias_z;
-    packet.pin_quick_connector = pin_quick_connector;
     packet.battery_voltage = battery_voltage;
     packet.cam_battery_voltage = cam_battery_voltage;
-    packet.current_consumption = current_consumption;
     packet.temperature = temperature;
     packet.ada_state = ada_state;
     packet.fmm_state = fmm_state;
@@ -360,7 +343,6 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
     packet.pin_nosecone = pin_nosecone;
     packet.pin_expulsion = pin_expulsion;
     packet.cutter_presence = cutter_presence;
-    packet.logger_error = logger_error;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
 #endif
@@ -380,7 +362,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
  * @param fmm_state  Flight Mode Manager State
  * @param dpl_state  Deployment Controller State
  * @param abk_state  Airbrake FSM state
- * @param nas_state  Navigation System FSM State
+ * @param nas_state  NAS FSM State
  * @param mea_state  MEA Controller State
  * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
  * @param pressure_digi [Pa] Pressure from digital sensor
@@ -404,34 +386,31 @@ 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 nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x  Navigation system gyroscope bias on x axis
- * @param nas_bias_y  Navigation system gyroscope bias on y axis
- * @param nas_bias_z  Navigation system gyroscope bias on z axis
- * @param pin_quick_connector   Quick connector detach pin 
+ * @param nas_n [deg] NAS estimated noth position
+ * @param nas_e [deg] NAS estimated east position
+ * @param nas_d [m] NAS estimated down position
+ * @param nas_vn [m/s] NAS estimated north velocity
+ * @param nas_ve [m/s] NAS estimated east velocity
+ * @param nas_vd [m/s] NAS estimated down velocity
+ * @param nas_qx [deg] NAS estimated attitude (qx)
+ * @param nas_qy [deg] NAS estimated attitude (qy)
+ * @param nas_qz [deg] NAS estimated attitude (qz)
+ * @param nas_qw [deg] NAS estimated attitude (qw)
+ * @param nas_bias_x  NAS gyroscope bias on x axis
+ * @param nas_bias_y  NAS gyroscope bias on y axis
+ * @param nas_bias_z  NAS gyroscope bias on z axis
  * @param pin_launch  Launch pin status (1 = connected, 0 = disconnected)
  * @param pin_nosecone  Nosecone pin status (1 = connected, 0 = disconnected)
  * @param pin_expulsion  Servo sensor status (1 = actuated, 0 = idle)
  * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
  * @param battery_voltage [V] Battery voltage
  * @param cam_battery_voltage [V] Camera battery voltage
- * @param 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,uint8_t mea_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float ada_vert_speed,float mea_mass,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float abk_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float pin_quick_connector,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t pin_expulsion,uint8_t cutter_presence,float battery_voltage,float cam_battery_voltage,float current_consumption,float temperature,int8_t logger_error)
+                                   uint64_t timestamp,uint8_t ada_state,uint8_t fmm_state,uint8_t dpl_state,uint8_t abk_state,uint8_t nas_state,uint8_t mea_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float ada_vert_speed,float mea_mass,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float abk_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t pin_expulsion,uint8_t cutter_presence,float battery_voltage,float cam_battery_voltage,float temperature)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
@@ -470,23 +449,20 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id,
     _mav_put_float(buf, 132, nas_bias_x);
     _mav_put_float(buf, 136, nas_bias_y);
     _mav_put_float(buf, 140, nas_bias_z);
-    _mav_put_float(buf, 144, pin_quick_connector);
-    _mav_put_float(buf, 148, battery_voltage);
-    _mav_put_float(buf, 152, cam_battery_voltage);
-    _mav_put_float(buf, 156, current_consumption);
-    _mav_put_float(buf, 160, temperature);
-    _mav_put_uint8_t(buf, 164, ada_state);
-    _mav_put_uint8_t(buf, 165, fmm_state);
-    _mav_put_uint8_t(buf, 166, dpl_state);
-    _mav_put_uint8_t(buf, 167, abk_state);
-    _mav_put_uint8_t(buf, 168, nas_state);
-    _mav_put_uint8_t(buf, 169, mea_state);
-    _mav_put_uint8_t(buf, 170, gps_fix);
-    _mav_put_uint8_t(buf, 171, pin_launch);
-    _mav_put_uint8_t(buf, 172, pin_nosecone);
-    _mav_put_uint8_t(buf, 173, pin_expulsion);
-    _mav_put_uint8_t(buf, 174, cutter_presence);
-    _mav_put_int8_t(buf, 175, logger_error);
+    _mav_put_float(buf, 144, battery_voltage);
+    _mav_put_float(buf, 148, cam_battery_voltage);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, ada_state);
+    _mav_put_uint8_t(buf, 157, fmm_state);
+    _mav_put_uint8_t(buf, 158, dpl_state);
+    _mav_put_uint8_t(buf, 159, abk_state);
+    _mav_put_uint8_t(buf, 160, nas_state);
+    _mav_put_uint8_t(buf, 161, mea_state);
+    _mav_put_uint8_t(buf, 162, gps_fix);
+    _mav_put_uint8_t(buf, 163, pin_launch);
+    _mav_put_uint8_t(buf, 164, pin_nosecone);
+    _mav_put_uint8_t(buf, 165, pin_expulsion);
+    _mav_put_uint8_t(buf, 166, cutter_presence);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
 #else
@@ -526,10 +502,8 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id,
     packet.nas_bias_x = nas_bias_x;
     packet.nas_bias_y = nas_bias_y;
     packet.nas_bias_z = nas_bias_z;
-    packet.pin_quick_connector = pin_quick_connector;
     packet.battery_voltage = battery_voltage;
     packet.cam_battery_voltage = cam_battery_voltage;
-    packet.current_consumption = current_consumption;
     packet.temperature = temperature;
     packet.ada_state = ada_state;
     packet.fmm_state = fmm_state;
@@ -542,7 +516,6 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id,
     packet.pin_nosecone = pin_nosecone;
     packet.pin_expulsion = pin_expulsion;
     packet.cutter_presence = cutter_presence;
-    packet.logger_error = logger_error;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
 #endif
@@ -561,7 +534,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id,
  */
 static inline uint16_t mavlink_msg_rocket_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
 {
-    return mavlink_msg_rocket_flight_tm_pack(system_id, component_id, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_quick_connector, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
+    return mavlink_msg_rocket_flight_tm_pack(system_id, component_id, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->temperature);
 }
 
 /**
@@ -575,7 +548,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode(uint8_t system_id, ui
  */
 static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
 {
-    return mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, chan, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_quick_connector, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
+    return mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, chan, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->temperature);
 }
 
 /**
@@ -587,7 +560,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_i
  * @param fmm_state  Flight Mode Manager State
  * @param dpl_state  Deployment Controller State
  * @param abk_state  Airbrake FSM state
- * @param nas_state  Navigation System FSM State
+ * @param nas_state  NAS FSM State
  * @param mea_state  MEA Controller State
  * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
  * @param pressure_digi [Pa] Pressure from digital sensor
@@ -611,33 +584,30 @@ 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 nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x  Navigation system gyroscope bias on x axis
- * @param nas_bias_y  Navigation system gyroscope bias on y axis
- * @param nas_bias_z  Navigation system gyroscope bias on z axis
- * @param pin_quick_connector   Quick connector detach pin 
+ * @param nas_n [deg] NAS estimated noth position
+ * @param nas_e [deg] NAS estimated east position
+ * @param nas_d [m] NAS estimated down position
+ * @param nas_vn [m/s] NAS estimated north velocity
+ * @param nas_ve [m/s] NAS estimated east velocity
+ * @param nas_vd [m/s] NAS estimated down velocity
+ * @param nas_qx [deg] NAS estimated attitude (qx)
+ * @param nas_qy [deg] NAS estimated attitude (qy)
+ * @param nas_qz [deg] NAS estimated attitude (qz)
+ * @param nas_qw [deg] NAS estimated attitude (qw)
+ * @param nas_bias_x  NAS gyroscope bias on x axis
+ * @param nas_bias_y  NAS gyroscope bias on y axis
+ * @param nas_bias_z  NAS gyroscope bias on z axis
  * @param pin_launch  Launch pin status (1 = connected, 0 = disconnected)
  * @param pin_nosecone  Nosecone pin status (1 = connected, 0 = disconnected)
  * @param pin_expulsion  Servo sensor status (1 = actuated, 0 = idle)
  * @param cutter_presence  Cutter presence status (1 = present, 0 = missing)
  * @param battery_voltage [V] Battery voltage
  * @param cam_battery_voltage [V] Camera battery voltage
- * @param 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, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float pin_quick_connector, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
+static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float temperature)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
@@ -676,23 +646,20 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin
     _mav_put_float(buf, 132, nas_bias_x);
     _mav_put_float(buf, 136, nas_bias_y);
     _mav_put_float(buf, 140, nas_bias_z);
-    _mav_put_float(buf, 144, pin_quick_connector);
-    _mav_put_float(buf, 148, battery_voltage);
-    _mav_put_float(buf, 152, cam_battery_voltage);
-    _mav_put_float(buf, 156, current_consumption);
-    _mav_put_float(buf, 160, temperature);
-    _mav_put_uint8_t(buf, 164, ada_state);
-    _mav_put_uint8_t(buf, 165, fmm_state);
-    _mav_put_uint8_t(buf, 166, dpl_state);
-    _mav_put_uint8_t(buf, 167, abk_state);
-    _mav_put_uint8_t(buf, 168, nas_state);
-    _mav_put_uint8_t(buf, 169, mea_state);
-    _mav_put_uint8_t(buf, 170, gps_fix);
-    _mav_put_uint8_t(buf, 171, pin_launch);
-    _mav_put_uint8_t(buf, 172, pin_nosecone);
-    _mav_put_uint8_t(buf, 173, pin_expulsion);
-    _mav_put_uint8_t(buf, 174, cutter_presence);
-    _mav_put_int8_t(buf, 175, logger_error);
+    _mav_put_float(buf, 144, battery_voltage);
+    _mav_put_float(buf, 148, cam_battery_voltage);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, ada_state);
+    _mav_put_uint8_t(buf, 157, fmm_state);
+    _mav_put_uint8_t(buf, 158, dpl_state);
+    _mav_put_uint8_t(buf, 159, abk_state);
+    _mav_put_uint8_t(buf, 160, nas_state);
+    _mav_put_uint8_t(buf, 161, mea_state);
+    _mav_put_uint8_t(buf, 162, gps_fix);
+    _mav_put_uint8_t(buf, 163, pin_launch);
+    _mav_put_uint8_t(buf, 164, pin_nosecone);
+    _mav_put_uint8_t(buf, 165, pin_expulsion);
+    _mav_put_uint8_t(buf, 166, cutter_presence);
 
     _mav_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
@@ -732,10 +699,8 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin
     packet.nas_bias_x = nas_bias_x;
     packet.nas_bias_y = nas_bias_y;
     packet.nas_bias_z = nas_bias_z;
-    packet.pin_quick_connector = pin_quick_connector;
     packet.battery_voltage = battery_voltage;
     packet.cam_battery_voltage = cam_battery_voltage;
-    packet.current_consumption = current_consumption;
     packet.temperature = temperature;
     packet.ada_state = ada_state;
     packet.fmm_state = fmm_state;
@@ -748,7 +713,6 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin
     packet.pin_nosecone = pin_nosecone;
     packet.pin_expulsion = pin_expulsion;
     packet.cutter_presence = cutter_presence;
-    packet.logger_error = logger_error;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)&packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
 #endif
@@ -762,7 +726,7 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin
 static inline void mavlink_msg_rocket_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_rocket_flight_tm_send(chan, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_quick_connector, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
+    mavlink_msg_rocket_flight_tm_send(chan, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->temperature);
 #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
@@ -776,7 +740,7 @@ static inline void mavlink_msg_rocket_flight_tm_send_struct(mavlink_channel_t ch
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float pin_quick_connector, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
+static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float temperature)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -815,23 +779,20 @@ static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgb
     _mav_put_float(buf, 132, nas_bias_x);
     _mav_put_float(buf, 136, nas_bias_y);
     _mav_put_float(buf, 140, nas_bias_z);
-    _mav_put_float(buf, 144, pin_quick_connector);
-    _mav_put_float(buf, 148, battery_voltage);
-    _mav_put_float(buf, 152, cam_battery_voltage);
-    _mav_put_float(buf, 156, current_consumption);
-    _mav_put_float(buf, 160, temperature);
-    _mav_put_uint8_t(buf, 164, ada_state);
-    _mav_put_uint8_t(buf, 165, fmm_state);
-    _mav_put_uint8_t(buf, 166, dpl_state);
-    _mav_put_uint8_t(buf, 167, abk_state);
-    _mav_put_uint8_t(buf, 168, nas_state);
-    _mav_put_uint8_t(buf, 169, mea_state);
-    _mav_put_uint8_t(buf, 170, gps_fix);
-    _mav_put_uint8_t(buf, 171, pin_launch);
-    _mav_put_uint8_t(buf, 172, pin_nosecone);
-    _mav_put_uint8_t(buf, 173, pin_expulsion);
-    _mav_put_uint8_t(buf, 174, cutter_presence);
-    _mav_put_int8_t(buf, 175, logger_error);
+    _mav_put_float(buf, 144, battery_voltage);
+    _mav_put_float(buf, 148, cam_battery_voltage);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, ada_state);
+    _mav_put_uint8_t(buf, 157, fmm_state);
+    _mav_put_uint8_t(buf, 158, dpl_state);
+    _mav_put_uint8_t(buf, 159, abk_state);
+    _mav_put_uint8_t(buf, 160, nas_state);
+    _mav_put_uint8_t(buf, 161, mea_state);
+    _mav_put_uint8_t(buf, 162, gps_fix);
+    _mav_put_uint8_t(buf, 163, pin_launch);
+    _mav_put_uint8_t(buf, 164, pin_nosecone);
+    _mav_put_uint8_t(buf, 165, pin_expulsion);
+    _mav_put_uint8_t(buf, 166, cutter_presence);
 
     _mav_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
@@ -871,10 +832,8 @@ static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgb
     packet->nas_bias_x = nas_bias_x;
     packet->nas_bias_y = nas_bias_y;
     packet->nas_bias_z = nas_bias_z;
-    packet->pin_quick_connector = pin_quick_connector;
     packet->battery_voltage = battery_voltage;
     packet->cam_battery_voltage = cam_battery_voltage;
-    packet->current_consumption = current_consumption;
     packet->temperature = temperature;
     packet->ada_state = ada_state;
     packet->fmm_state = fmm_state;
@@ -887,7 +846,6 @@ static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgb
     packet->pin_nosecone = pin_nosecone;
     packet->pin_expulsion = pin_expulsion;
     packet->cutter_presence = cutter_presence;
-    packet->logger_error = logger_error;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
 #endif
@@ -916,7 +874,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,  164);
+    return _MAV_RETURN_uint8_t(msg,  156);
 }
 
 /**
@@ -926,7 +884,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,  165);
+    return _MAV_RETURN_uint8_t(msg,  157);
 }
 
 /**
@@ -936,7 +894,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,  166);
+    return _MAV_RETURN_uint8_t(msg,  158);
 }
 
 /**
@@ -946,17 +904,17 @@ 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,  167);
+    return _MAV_RETURN_uint8_t(msg,  159);
 }
 
 /**
  * @brief Get field nas_state from rocket_flight_tm message
  *
- * @return  Navigation System FSM State
+ * @return  NAS FSM State
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_nas_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  168);
+    return _MAV_RETURN_uint8_t(msg,  160);
 }
 
 /**
@@ -966,7 +924,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_nas_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_mea_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  169);
+    return _MAV_RETURN_uint8_t(msg,  161);
 }
 
 /**
@@ -1146,7 +1104,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,  170);
+    return _MAV_RETURN_uint8_t(msg,  162);
 }
 
 /**
@@ -1192,7 +1150,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_abk_angle(const mavlink_mes
 /**
  * @brief Get field nas_n from rocket_flight_tm message
  *
- * @return [deg] Navigation system estimated noth position
+ * @return [deg] NAS estimated noth position
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_n(const mavlink_message_t* msg)
 {
@@ -1202,7 +1160,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_n(const mavlink_message
 /**
  * @brief Get field nas_e from rocket_flight_tm message
  *
- * @return [deg] Navigation system estimated east position
+ * @return [deg] NAS estimated east position
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_e(const mavlink_message_t* msg)
 {
@@ -1212,7 +1170,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_e(const mavlink_message
 /**
  * @brief Get field nas_d from rocket_flight_tm message
  *
- * @return [m] Navigation system estimated down position
+ * @return [m] NAS estimated down position
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_d(const mavlink_message_t* msg)
 {
@@ -1222,7 +1180,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_d(const mavlink_message
 /**
  * @brief Get field nas_vn from rocket_flight_tm message
  *
- * @return [m/s] Navigation system estimated north velocity
+ * @return [m/s] NAS estimated north velocity
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_vn(const mavlink_message_t* msg)
 {
@@ -1232,7 +1190,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_vn(const mavlink_messag
 /**
  * @brief Get field nas_ve from rocket_flight_tm message
  *
- * @return [m/s] Navigation system estimated east velocity
+ * @return [m/s] NAS estimated east velocity
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_ve(const mavlink_message_t* msg)
 {
@@ -1242,7 +1200,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_ve(const mavlink_messag
 /**
  * @brief Get field nas_vd from rocket_flight_tm message
  *
- * @return [m/s] Navigation system estimated down velocity
+ * @return [m/s] NAS estimated down velocity
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_vd(const mavlink_message_t* msg)
 {
@@ -1252,7 +1210,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_vd(const mavlink_messag
 /**
  * @brief Get field nas_qx from rocket_flight_tm message
  *
- * @return [deg] Navigation system estimated attitude (qx)
+ * @return [deg] NAS estimated attitude (qx)
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_qx(const mavlink_message_t* msg)
 {
@@ -1262,7 +1220,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_qx(const mavlink_messag
 /**
  * @brief Get field nas_qy from rocket_flight_tm message
  *
- * @return [deg] Navigation system estimated attitude (qy)
+ * @return [deg] NAS estimated attitude (qy)
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_qy(const mavlink_message_t* msg)
 {
@@ -1272,7 +1230,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_qy(const mavlink_messag
 /**
  * @brief Get field nas_qz from rocket_flight_tm message
  *
- * @return [deg] Navigation system estimated attitude (qz)
+ * @return [deg] NAS estimated attitude (qz)
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_qz(const mavlink_message_t* msg)
 {
@@ -1282,7 +1240,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_qz(const mavlink_messag
 /**
  * @brief Get field nas_qw from rocket_flight_tm message
  *
- * @return [deg] Navigation system estimated attitude (qw)
+ * @return [deg] NAS estimated attitude (qw)
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_qw(const mavlink_message_t* msg)
 {
@@ -1292,7 +1250,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_qw(const mavlink_messag
 /**
  * @brief Get field nas_bias_x from rocket_flight_tm message
  *
- * @return  Navigation system gyroscope bias on x axis
+ * @return  NAS gyroscope bias on x axis
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_x(const mavlink_message_t* msg)
 {
@@ -1302,7 +1260,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_x(const mavlink_me
 /**
  * @brief Get field nas_bias_y from rocket_flight_tm message
  *
- * @return  Navigation system gyroscope bias on y axis
+ * @return  NAS gyroscope bias on y axis
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_y(const mavlink_message_t* msg)
 {
@@ -1312,23 +1270,13 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_y(const mavlink_me
 /**
  * @brief Get field nas_bias_z from rocket_flight_tm message
  *
- * @return  Navigation system gyroscope bias on z axis
+ * @return  NAS gyroscope bias on z axis
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_z(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_float(msg,  140);
 }
 
-/**
- * @brief Get field pin_quick_connector from rocket_flight_tm message
- *
- * @return   Quick connector detach pin 
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pin_quick_connector(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_float(msg,  144);
-}
-
 /**
  * @brief Get field pin_launch from rocket_flight_tm message
  *
@@ -1336,7 +1284,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_pin_quick_connector(const m
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_launch(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  171);
+    return _MAV_RETURN_uint8_t(msg,  163);
 }
 
 /**
@@ -1346,7 +1294,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,  172);
+    return _MAV_RETURN_uint8_t(msg,  164);
 }
 
 /**
@@ -1356,7 +1304,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,  173);
+    return _MAV_RETURN_uint8_t(msg,  165);
 }
 
 /**
@@ -1366,7 +1314,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_expulsion(const mavli
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_cutter_presence(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  174);
+    return _MAV_RETURN_uint8_t(msg,  166);
 }
 
 /**
@@ -1376,7 +1324,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_cutter_presence(const mav
  */
 static inline float mavlink_msg_rocket_flight_tm_get_battery_voltage(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  148);
+    return _MAV_RETURN_float(msg,  144);
 }
 
 /**
@@ -1386,17 +1334,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_battery_voltage(const mavli
  */
 static inline float mavlink_msg_rocket_flight_tm_get_cam_battery_voltage(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  152);
-}
-
-/**
- * @brief Get field current_consumption from rocket_flight_tm message
- *
- * @return [A] Battery current
- */
-static inline float mavlink_msg_rocket_flight_tm_get_current_consumption(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_float(msg,  156);
+    return _MAV_RETURN_float(msg,  148);
 }
 
 /**
@@ -1406,17 +1344,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_current_consumption(const m
  */
 static inline float mavlink_msg_rocket_flight_tm_get_temperature(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  160);
-}
-
-/**
- * @brief Get field logger_error from rocket_flight_tm message
- *
- * @return  Logger error (0 = no error, -1 otherwise)
- */
-static inline int8_t mavlink_msg_rocket_flight_tm_get_logger_error(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_int8_t(msg,  175);
+    return _MAV_RETURN_float(msg,  152);
 }
 
 /**
@@ -1463,10 +1391,8 @@ static inline void mavlink_msg_rocket_flight_tm_decode(const mavlink_message_t*
     rocket_flight_tm->nas_bias_x = mavlink_msg_rocket_flight_tm_get_nas_bias_x(msg);
     rocket_flight_tm->nas_bias_y = mavlink_msg_rocket_flight_tm_get_nas_bias_y(msg);
     rocket_flight_tm->nas_bias_z = mavlink_msg_rocket_flight_tm_get_nas_bias_z(msg);
-    rocket_flight_tm->pin_quick_connector = mavlink_msg_rocket_flight_tm_get_pin_quick_connector(msg);
     rocket_flight_tm->battery_voltage = mavlink_msg_rocket_flight_tm_get_battery_voltage(msg);
     rocket_flight_tm->cam_battery_voltage = mavlink_msg_rocket_flight_tm_get_cam_battery_voltage(msg);
-    rocket_flight_tm->current_consumption = mavlink_msg_rocket_flight_tm_get_current_consumption(msg);
     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);
@@ -1479,7 +1405,6 @@ static inline void mavlink_msg_rocket_flight_tm_decode(const mavlink_message_t*
     rocket_flight_tm->pin_nosecone = mavlink_msg_rocket_flight_tm_get_pin_nosecone(msg);
     rocket_flight_tm->pin_expulsion = mavlink_msg_rocket_flight_tm_get_pin_expulsion(msg);
     rocket_flight_tm->cutter_presence = mavlink_msg_rocket_flight_tm_get_cutter_presence(msg);
-    rocket_flight_tm->logger_error = mavlink_msg_rocket_flight_tm_get_logger_error(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN? msg->len : MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN;
         memset(rocket_flight_tm, 0, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_rocket_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_rocket_stats_tm.h
index c878c468511c88c92b03ee5caa9a8f0ce437a766..0c590515b87c2d56bc12f69423229ff4a6c2b1d9 100644
--- a/mavlink_lib/lyra/mavlink_msg_rocket_stats_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_rocket_stats_tm.h
@@ -20,18 +20,26 @@ typedef struct __mavlink_rocket_stats_tm_t {
  float apogee_alt; /*< [m] Apogee altitude*/
  float min_pressure; /*< [Pa] Apogee pressure - Digital barometer*/
  float ada_min_pressure; /*< [Pa] Apogee pressure - ADA filtered*/
- float dpl_vane_max_pressure; /*< [Pa] Max pressure in the deployment bay during drogue deployment*/
+ float dpl_bay_max_pressure; /*< [Pa] Max pressure in the deployment bay during drogue deployment*/
  float cpu_load; /*<  CPU load in percentage*/
  uint32_t free_heap; /*<  Amount of available heap in memory*/
+ int32_t log_good; /*<  0 if log failed, 1 otherwise*/
+ int16_t log_number; /*<  Currently active log file, -1 if the logger is inactive*/
+ uint8_t payload_board_state; /*<  Main board fmm state*/
+ uint8_t motor_board_state; /*<  Motor board fmm state*/
+ uint8_t payload_can_status; /*<  Main CAN status*/
+ uint8_t motor_can_status; /*<  Motor CAN status*/
+ uint8_t rig_can_status; /*<  RIG CAN status*/
+ uint8_t hil_state; /*<  1 if the board is currently in HIL mode*/
 } mavlink_rocket_stats_tm_t;
 
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN 92
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN 92
-#define MAVLINK_MSG_ID_210_LEN 92
-#define MAVLINK_MSG_ID_210_MIN_LEN 92
+#define MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN 104
+#define MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN 104
+#define MAVLINK_MSG_ID_210_LEN 104
+#define MAVLINK_MSG_ID_210_MIN_LEN 104
 
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC 245
-#define MAVLINK_MSG_ID_210_CRC 245
+#define MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC 46
+#define MAVLINK_MSG_ID_210_CRC 46
 
 
 
@@ -39,7 +47,7 @@ typedef struct __mavlink_rocket_stats_tm_t {
 #define MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM { \
     210, \
     "ROCKET_STATS_TM", \
-    18, \
+    26, \
     {  { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_stats_tm_t, liftoff_ts) }, \
          { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc_ts) }, \
          { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc) }, \
@@ -55,15 +63,23 @@ typedef struct __mavlink_rocket_stats_tm_t {
          { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_stats_tm_t, apogee_alt) }, \
          { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_stats_tm_t, min_pressure) }, \
          { "ada_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_stats_tm_t, ada_min_pressure) }, \
-         { "dpl_vane_max_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_stats_tm_t, dpl_vane_max_pressure) }, \
+         { "dpl_bay_max_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_stats_tm_t, dpl_bay_max_pressure) }, \
          { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_stats_tm_t, cpu_load) }, \
          { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 88, offsetof(mavlink_rocket_stats_tm_t, free_heap) }, \
+         { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 96, offsetof(mavlink_rocket_stats_tm_t, log_number) }, \
+         { "log_good", NULL, MAVLINK_TYPE_INT32_T, 0, 92, offsetof(mavlink_rocket_stats_tm_t, log_good) }, \
+         { "payload_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 98, offsetof(mavlink_rocket_stats_tm_t, payload_board_state) }, \
+         { "motor_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 99, offsetof(mavlink_rocket_stats_tm_t, motor_board_state) }, \
+         { "payload_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 100, offsetof(mavlink_rocket_stats_tm_t, payload_can_status) }, \
+         { "motor_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 101, offsetof(mavlink_rocket_stats_tm_t, motor_can_status) }, \
+         { "rig_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 102, offsetof(mavlink_rocket_stats_tm_t, rig_can_status) }, \
+         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 103, offsetof(mavlink_rocket_stats_tm_t, hil_state) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM { \
     "ROCKET_STATS_TM", \
-    18, \
+    26, \
     {  { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_stats_tm_t, liftoff_ts) }, \
          { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc_ts) }, \
          { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc) }, \
@@ -79,9 +95,17 @@ typedef struct __mavlink_rocket_stats_tm_t {
          { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_stats_tm_t, apogee_alt) }, \
          { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_stats_tm_t, min_pressure) }, \
          { "ada_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_stats_tm_t, ada_min_pressure) }, \
-         { "dpl_vane_max_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_stats_tm_t, dpl_vane_max_pressure) }, \
+         { "dpl_bay_max_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_stats_tm_t, dpl_bay_max_pressure) }, \
          { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_stats_tm_t, cpu_load) }, \
          { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 88, offsetof(mavlink_rocket_stats_tm_t, free_heap) }, \
+         { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 96, offsetof(mavlink_rocket_stats_tm_t, log_number) }, \
+         { "log_good", NULL, MAVLINK_TYPE_INT32_T, 0, 92, offsetof(mavlink_rocket_stats_tm_t, log_good) }, \
+         { "payload_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 98, offsetof(mavlink_rocket_stats_tm_t, payload_board_state) }, \
+         { "motor_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 99, offsetof(mavlink_rocket_stats_tm_t, motor_board_state) }, \
+         { "payload_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 100, offsetof(mavlink_rocket_stats_tm_t, payload_can_status) }, \
+         { "motor_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 101, offsetof(mavlink_rocket_stats_tm_t, motor_can_status) }, \
+         { "rig_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 102, offsetof(mavlink_rocket_stats_tm_t, rig_can_status) }, \
+         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 103, offsetof(mavlink_rocket_stats_tm_t, hil_state) }, \
          } \
 }
 #endif
@@ -107,13 +131,21 @@ typedef struct __mavlink_rocket_stats_tm_t {
  * @param apogee_alt [m] Apogee altitude
  * @param min_pressure [Pa] Apogee pressure - Digital barometer
  * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
+ * @param dpl_bay_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
  * @param cpu_load  CPU load in percentage
  * @param free_heap  Amount of available heap in memory
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param log_good  0 if log failed, 1 otherwise
+ * @param payload_board_state  Main board fmm state
+ * @param motor_board_state  Motor board fmm state
+ * @param payload_can_status  Main CAN status
+ * @param motor_can_status  Motor CAN status
+ * @param rig_can_status  RIG CAN status
+ * @param hil_state  1 if the board is currently in HIL mode
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_rocket_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_vane_max_pressure, float cpu_load, uint32_t free_heap)
+                               uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_bay_max_pressure, float cpu_load, uint32_t free_heap, int16_t log_number, int32_t log_good, uint8_t payload_board_state, uint8_t motor_board_state, uint8_t payload_can_status, uint8_t motor_can_status, uint8_t rig_can_status, uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
@@ -132,9 +164,17 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_pack(uint8_t system_id, uint8
     _mav_put_float(buf, 68, apogee_alt);
     _mav_put_float(buf, 72, min_pressure);
     _mav_put_float(buf, 76, ada_min_pressure);
-    _mav_put_float(buf, 80, dpl_vane_max_pressure);
+    _mav_put_float(buf, 80, dpl_bay_max_pressure);
     _mav_put_float(buf, 84, cpu_load);
     _mav_put_uint32_t(buf, 88, free_heap);
+    _mav_put_int32_t(buf, 92, log_good);
+    _mav_put_int16_t(buf, 96, log_number);
+    _mav_put_uint8_t(buf, 98, payload_board_state);
+    _mav_put_uint8_t(buf, 99, motor_board_state);
+    _mav_put_uint8_t(buf, 100, payload_can_status);
+    _mav_put_uint8_t(buf, 101, motor_can_status);
+    _mav_put_uint8_t(buf, 102, rig_can_status);
+    _mav_put_uint8_t(buf, 103, hil_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
 #else
@@ -154,9 +194,17 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_pack(uint8_t system_id, uint8
     packet.apogee_alt = apogee_alt;
     packet.min_pressure = min_pressure;
     packet.ada_min_pressure = ada_min_pressure;
-    packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
+    packet.dpl_bay_max_pressure = dpl_bay_max_pressure;
     packet.cpu_load = cpu_load;
     packet.free_heap = free_heap;
+    packet.log_good = log_good;
+    packet.log_number = log_number;
+    packet.payload_board_state = payload_board_state;
+    packet.motor_board_state = motor_board_state;
+    packet.payload_can_status = payload_can_status;
+    packet.motor_can_status = motor_can_status;
+    packet.rig_can_status = rig_can_status;
+    packet.hil_state = hil_state;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
 #endif
@@ -186,14 +234,22 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_pack(uint8_t system_id, uint8
  * @param apogee_alt [m] Apogee altitude
  * @param min_pressure [Pa] Apogee pressure - Digital barometer
  * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
+ * @param dpl_bay_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
  * @param cpu_load  CPU load in percentage
  * @param free_heap  Amount of available heap in memory
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param log_good  0 if log failed, 1 otherwise
+ * @param payload_board_state  Main board fmm state
+ * @param motor_board_state  Motor board fmm state
+ * @param payload_can_status  Main CAN status
+ * @param motor_can_status  Motor CAN status
+ * @param rig_can_status  RIG CAN status
+ * @param hil_state  1 if the board is currently in HIL mode
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_rocket_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t liftoff_ts,uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t dpl_ts,float dpl_max_acc,uint64_t max_z_speed_ts,float max_z_speed,float max_airspeed_pitot,float max_speed_altitude,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float apogee_alt,float min_pressure,float ada_min_pressure,float dpl_vane_max_pressure,float cpu_load,uint32_t free_heap)
+                                   uint64_t liftoff_ts,uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t dpl_ts,float dpl_max_acc,uint64_t max_z_speed_ts,float max_z_speed,float max_airspeed_pitot,float max_speed_altitude,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float apogee_alt,float min_pressure,float ada_min_pressure,float dpl_bay_max_pressure,float cpu_load,uint32_t free_heap,int16_t log_number,int32_t log_good,uint8_t payload_board_state,uint8_t motor_board_state,uint8_t payload_can_status,uint8_t motor_can_status,uint8_t rig_can_status,uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
@@ -212,9 +268,17 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_pack_chan(uint8_t system_id,
     _mav_put_float(buf, 68, apogee_alt);
     _mav_put_float(buf, 72, min_pressure);
     _mav_put_float(buf, 76, ada_min_pressure);
-    _mav_put_float(buf, 80, dpl_vane_max_pressure);
+    _mav_put_float(buf, 80, dpl_bay_max_pressure);
     _mav_put_float(buf, 84, cpu_load);
     _mav_put_uint32_t(buf, 88, free_heap);
+    _mav_put_int32_t(buf, 92, log_good);
+    _mav_put_int16_t(buf, 96, log_number);
+    _mav_put_uint8_t(buf, 98, payload_board_state);
+    _mav_put_uint8_t(buf, 99, motor_board_state);
+    _mav_put_uint8_t(buf, 100, payload_can_status);
+    _mav_put_uint8_t(buf, 101, motor_can_status);
+    _mav_put_uint8_t(buf, 102, rig_can_status);
+    _mav_put_uint8_t(buf, 103, hil_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
 #else
@@ -234,9 +298,17 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_pack_chan(uint8_t system_id,
     packet.apogee_alt = apogee_alt;
     packet.min_pressure = min_pressure;
     packet.ada_min_pressure = ada_min_pressure;
-    packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
+    packet.dpl_bay_max_pressure = dpl_bay_max_pressure;
     packet.cpu_load = cpu_load;
     packet.free_heap = free_heap;
+    packet.log_good = log_good;
+    packet.log_number = log_number;
+    packet.payload_board_state = payload_board_state;
+    packet.motor_board_state = motor_board_state;
+    packet.payload_can_status = payload_can_status;
+    packet.motor_can_status = motor_can_status;
+    packet.rig_can_status = rig_can_status;
+    packet.hil_state = hil_state;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
 #endif
@@ -255,7 +327,7 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_pack_chan(uint8_t system_id,
  */
 static inline uint16_t mavlink_msg_rocket_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
 {
-    return mavlink_msg_rocket_stats_tm_pack(system_id, component_id, msg, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_vane_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap);
+    return mavlink_msg_rocket_stats_tm_pack(system_id, component_id, msg, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_bay_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap, rocket_stats_tm->log_number, rocket_stats_tm->log_good, rocket_stats_tm->payload_board_state, rocket_stats_tm->motor_board_state, rocket_stats_tm->payload_can_status, rocket_stats_tm->motor_can_status, rocket_stats_tm->rig_can_status, rocket_stats_tm->hil_state);
 }
 
 /**
@@ -269,7 +341,7 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_encode(uint8_t system_id, uin
  */
 static inline uint16_t mavlink_msg_rocket_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
 {
-    return mavlink_msg_rocket_stats_tm_pack_chan(system_id, component_id, chan, msg, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_vane_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap);
+    return mavlink_msg_rocket_stats_tm_pack_chan(system_id, component_id, chan, msg, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_bay_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap, rocket_stats_tm->log_number, rocket_stats_tm->log_good, rocket_stats_tm->payload_board_state, rocket_stats_tm->motor_board_state, rocket_stats_tm->payload_can_status, rocket_stats_tm->motor_can_status, rocket_stats_tm->rig_can_status, rocket_stats_tm->hil_state);
 }
 
 /**
@@ -291,13 +363,21 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_encode_chan(uint8_t system_id
  * @param apogee_alt [m] Apogee altitude
  * @param min_pressure [Pa] Apogee pressure - Digital barometer
  * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
+ * @param dpl_bay_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
  * @param cpu_load  CPU load in percentage
  * @param free_heap  Amount of available heap in memory
+ * @param log_number  Currently active log file, -1 if the logger is inactive
+ * @param log_good  0 if log failed, 1 otherwise
+ * @param payload_board_state  Main board fmm state
+ * @param motor_board_state  Motor board fmm state
+ * @param payload_can_status  Main CAN status
+ * @param motor_can_status  Motor CAN status
+ * @param rig_can_status  RIG CAN status
+ * @param hil_state  1 if the board is currently in HIL mode
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_rocket_stats_tm_send(mavlink_channel_t chan, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_vane_max_pressure, float cpu_load, uint32_t free_heap)
+static inline void mavlink_msg_rocket_stats_tm_send(mavlink_channel_t chan, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_bay_max_pressure, float cpu_load, uint32_t free_heap, int16_t log_number, int32_t log_good, uint8_t payload_board_state, uint8_t motor_board_state, uint8_t payload_can_status, uint8_t motor_can_status, uint8_t rig_can_status, uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
@@ -316,9 +396,17 @@ static inline void mavlink_msg_rocket_stats_tm_send(mavlink_channel_t chan, uint
     _mav_put_float(buf, 68, apogee_alt);
     _mav_put_float(buf, 72, min_pressure);
     _mav_put_float(buf, 76, ada_min_pressure);
-    _mav_put_float(buf, 80, dpl_vane_max_pressure);
+    _mav_put_float(buf, 80, dpl_bay_max_pressure);
     _mav_put_float(buf, 84, cpu_load);
     _mav_put_uint32_t(buf, 88, free_heap);
+    _mav_put_int32_t(buf, 92, log_good);
+    _mav_put_int16_t(buf, 96, log_number);
+    _mav_put_uint8_t(buf, 98, payload_board_state);
+    _mav_put_uint8_t(buf, 99, motor_board_state);
+    _mav_put_uint8_t(buf, 100, payload_can_status);
+    _mav_put_uint8_t(buf, 101, motor_can_status);
+    _mav_put_uint8_t(buf, 102, rig_can_status);
+    _mav_put_uint8_t(buf, 103, hil_state);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
 #else
@@ -338,9 +426,17 @@ static inline void mavlink_msg_rocket_stats_tm_send(mavlink_channel_t chan, uint
     packet.apogee_alt = apogee_alt;
     packet.min_pressure = min_pressure;
     packet.ada_min_pressure = ada_min_pressure;
-    packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
+    packet.dpl_bay_max_pressure = dpl_bay_max_pressure;
     packet.cpu_load = cpu_load;
     packet.free_heap = free_heap;
+    packet.log_good = log_good;
+    packet.log_number = log_number;
+    packet.payload_board_state = payload_board_state;
+    packet.motor_board_state = motor_board_state;
+    packet.payload_can_status = payload_can_status;
+    packet.motor_can_status = motor_can_status;
+    packet.rig_can_status = rig_can_status;
+    packet.hil_state = hil_state;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
 #endif
@@ -354,7 +450,7 @@ static inline void mavlink_msg_rocket_stats_tm_send(mavlink_channel_t chan, uint
 static inline void mavlink_msg_rocket_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_rocket_stats_tm_send(chan, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_vane_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap);
+    mavlink_msg_rocket_stats_tm_send(chan, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_bay_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap, rocket_stats_tm->log_number, rocket_stats_tm->log_good, rocket_stats_tm->payload_board_state, rocket_stats_tm->motor_board_state, rocket_stats_tm->payload_can_status, rocket_stats_tm->motor_can_status, rocket_stats_tm->rig_can_status, rocket_stats_tm->hil_state);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, (const char *)rocket_stats_tm, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
 #endif
@@ -368,7 +464,7 @@ static inline void mavlink_msg_rocket_stats_tm_send_struct(mavlink_channel_t cha
   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_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_vane_max_pressure, float cpu_load, uint32_t free_heap)
+static inline void mavlink_msg_rocket_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_bay_max_pressure, float cpu_load, uint32_t free_heap, int16_t log_number, int32_t log_good, uint8_t payload_board_state, uint8_t motor_board_state, uint8_t payload_can_status, uint8_t motor_can_status, uint8_t rig_can_status, uint8_t hil_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -387,9 +483,17 @@ static inline void mavlink_msg_rocket_stats_tm_send_buf(mavlink_message_t *msgbu
     _mav_put_float(buf, 68, apogee_alt);
     _mav_put_float(buf, 72, min_pressure);
     _mav_put_float(buf, 76, ada_min_pressure);
-    _mav_put_float(buf, 80, dpl_vane_max_pressure);
+    _mav_put_float(buf, 80, dpl_bay_max_pressure);
     _mav_put_float(buf, 84, cpu_load);
     _mav_put_uint32_t(buf, 88, free_heap);
+    _mav_put_int32_t(buf, 92, log_good);
+    _mav_put_int16_t(buf, 96, log_number);
+    _mav_put_uint8_t(buf, 98, payload_board_state);
+    _mav_put_uint8_t(buf, 99, motor_board_state);
+    _mav_put_uint8_t(buf, 100, payload_can_status);
+    _mav_put_uint8_t(buf, 101, motor_can_status);
+    _mav_put_uint8_t(buf, 102, rig_can_status);
+    _mav_put_uint8_t(buf, 103, hil_state);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
 #else
@@ -409,9 +513,17 @@ static inline void mavlink_msg_rocket_stats_tm_send_buf(mavlink_message_t *msgbu
     packet->apogee_alt = apogee_alt;
     packet->min_pressure = min_pressure;
     packet->ada_min_pressure = ada_min_pressure;
-    packet->dpl_vane_max_pressure = dpl_vane_max_pressure;
+    packet->dpl_bay_max_pressure = dpl_bay_max_pressure;
     packet->cpu_load = cpu_load;
     packet->free_heap = free_heap;
+    packet->log_good = log_good;
+    packet->log_number = log_number;
+    packet->payload_board_state = payload_board_state;
+    packet->motor_board_state = motor_board_state;
+    packet->payload_can_status = payload_can_status;
+    packet->motor_can_status = motor_can_status;
+    packet->rig_can_status = rig_can_status;
+    packet->hil_state = hil_state;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
 #endif
@@ -574,11 +686,11 @@ static inline float mavlink_msg_rocket_stats_tm_get_ada_min_pressure(const mavli
 }
 
 /**
- * @brief Get field dpl_vane_max_pressure from rocket_stats_tm message
+ * @brief Get field dpl_bay_max_pressure from rocket_stats_tm message
  *
  * @return [Pa] Max pressure in the deployment bay during drogue deployment
  */
-static inline float mavlink_msg_rocket_stats_tm_get_dpl_vane_max_pressure(const mavlink_message_t* msg)
+static inline float mavlink_msg_rocket_stats_tm_get_dpl_bay_max_pressure(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_float(msg,  80);
 }
@@ -603,6 +715,86 @@ static inline uint32_t mavlink_msg_rocket_stats_tm_get_free_heap(const mavlink_m
     return _MAV_RETURN_uint32_t(msg,  88);
 }
 
+/**
+ * @brief Get field log_number from rocket_stats_tm message
+ *
+ * @return  Currently active log file, -1 if the logger is inactive
+ */
+static inline int16_t mavlink_msg_rocket_stats_tm_get_log_number(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  96);
+}
+
+/**
+ * @brief Get field log_good from rocket_stats_tm message
+ *
+ * @return  0 if log failed, 1 otherwise
+ */
+static inline int32_t mavlink_msg_rocket_stats_tm_get_log_good(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  92);
+}
+
+/**
+ * @brief Get field payload_board_state from rocket_stats_tm message
+ *
+ * @return  Main board fmm state
+ */
+static inline uint8_t mavlink_msg_rocket_stats_tm_get_payload_board_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  98);
+}
+
+/**
+ * @brief Get field motor_board_state from rocket_stats_tm message
+ *
+ * @return  Motor board fmm state
+ */
+static inline uint8_t mavlink_msg_rocket_stats_tm_get_motor_board_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  99);
+}
+
+/**
+ * @brief Get field payload_can_status from rocket_stats_tm message
+ *
+ * @return  Main CAN status
+ */
+static inline uint8_t mavlink_msg_rocket_stats_tm_get_payload_can_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  100);
+}
+
+/**
+ * @brief Get field motor_can_status from rocket_stats_tm message
+ *
+ * @return  Motor CAN status
+ */
+static inline uint8_t mavlink_msg_rocket_stats_tm_get_motor_can_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  101);
+}
+
+/**
+ * @brief Get field rig_can_status from rocket_stats_tm message
+ *
+ * @return  RIG CAN status
+ */
+static inline uint8_t mavlink_msg_rocket_stats_tm_get_rig_can_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  102);
+}
+
+/**
+ * @brief Get field hil_state from rocket_stats_tm message
+ *
+ * @return  1 if the board is currently in HIL mode
+ */
+static inline uint8_t mavlink_msg_rocket_stats_tm_get_hil_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  103);
+}
+
 /**
  * @brief Decode a rocket_stats_tm message into a struct
  *
@@ -627,9 +819,17 @@ static inline void mavlink_msg_rocket_stats_tm_decode(const mavlink_message_t* m
     rocket_stats_tm->apogee_alt = mavlink_msg_rocket_stats_tm_get_apogee_alt(msg);
     rocket_stats_tm->min_pressure = mavlink_msg_rocket_stats_tm_get_min_pressure(msg);
     rocket_stats_tm->ada_min_pressure = mavlink_msg_rocket_stats_tm_get_ada_min_pressure(msg);
-    rocket_stats_tm->dpl_vane_max_pressure = mavlink_msg_rocket_stats_tm_get_dpl_vane_max_pressure(msg);
+    rocket_stats_tm->dpl_bay_max_pressure = mavlink_msg_rocket_stats_tm_get_dpl_bay_max_pressure(msg);
     rocket_stats_tm->cpu_load = mavlink_msg_rocket_stats_tm_get_cpu_load(msg);
     rocket_stats_tm->free_heap = mavlink_msg_rocket_stats_tm_get_free_heap(msg);
+    rocket_stats_tm->log_good = mavlink_msg_rocket_stats_tm_get_log_good(msg);
+    rocket_stats_tm->log_number = mavlink_msg_rocket_stats_tm_get_log_number(msg);
+    rocket_stats_tm->payload_board_state = mavlink_msg_rocket_stats_tm_get_payload_board_state(msg);
+    rocket_stats_tm->motor_board_state = mavlink_msg_rocket_stats_tm_get_motor_board_state(msg);
+    rocket_stats_tm->payload_can_status = mavlink_msg_rocket_stats_tm_get_payload_can_status(msg);
+    rocket_stats_tm->motor_can_status = mavlink_msg_rocket_stats_tm_get_motor_can_status(msg);
+    rocket_stats_tm->rig_can_status = mavlink_msg_rocket_stats_tm_get_rig_can_status(msg);
+    rocket_stats_tm->hil_state = mavlink_msg_rocket_stats_tm_get_hil_state(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN;
         memset(rocket_stats_tm, 0, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_sensor_state_tm.h b/mavlink_lib/lyra/mavlink_msg_sensor_state_tm.h
index deec614076883a9d0a979da1a7b2c515b2d87361..f07dc0ac404bcf0e9a9cd927f836da2b935dbaf2 100644
--- a/mavlink_lib/lyra/mavlink_msg_sensor_state_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_sensor_state_tm.h
@@ -1,39 +1,42 @@
 #pragma once
 // MESSAGE SENSOR_STATE_TM PACKING
 
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM 111
+#define MAVLINK_MSG_ID_SENSOR_STATE_TM 112
 
 
 typedef struct __mavlink_sensor_state_tm_t {
  char sensor_name[20]; /*<  Sensor name*/
- uint8_t state; /*<  Boolean that represents the init state*/
+ uint8_t initialized; /*<  Boolean that represents the init state*/
+ uint8_t enabled; /*<  Boolean that represents the enabled state*/
 } mavlink_sensor_state_tm_t;
 
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN 21
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN 21
-#define MAVLINK_MSG_ID_111_LEN 21
-#define MAVLINK_MSG_ID_111_MIN_LEN 21
+#define MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN 22
+#define MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN 22
+#define MAVLINK_MSG_ID_112_LEN 22
+#define MAVLINK_MSG_ID_112_MIN_LEN 22
 
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC 155
-#define MAVLINK_MSG_ID_111_CRC 155
+#define MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC 165
+#define MAVLINK_MSG_ID_112_CRC 165
 
 #define MAVLINK_MSG_SENSOR_STATE_TM_FIELD_SENSOR_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM { \
-    111, \
+    112, \
     "SENSOR_STATE_TM", \
-    2, \
+    3, \
     {  { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 0, offsetof(mavlink_sensor_state_tm_t, sensor_name) }, \
-         { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_sensor_state_tm_t, state) }, \
+         { "initialized", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_sensor_state_tm_t, initialized) }, \
+         { "enabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_sensor_state_tm_t, enabled) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM { \
     "SENSOR_STATE_TM", \
-    2, \
+    3, \
     {  { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 0, offsetof(mavlink_sensor_state_tm_t, sensor_name) }, \
-         { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_sensor_state_tm_t, state) }, \
+         { "initialized", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_sensor_state_tm_t, initialized) }, \
+         { "enabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_sensor_state_tm_t, enabled) }, \
          } \
 }
 #endif
@@ -45,20 +48,23 @@ typedef struct __mavlink_sensor_state_tm_t {
  * @param msg The MAVLink message to compress the data into
  *
  * @param sensor_name  Sensor name
- * @param state  Boolean that represents the init state
+ * @param initialized  Boolean that represents the init state
+ * @param enabled  Boolean that represents the enabled state
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_sensor_state_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               const char *sensor_name, uint8_t state)
+                               const char *sensor_name, uint8_t initialized, uint8_t enabled)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
-    _mav_put_uint8_t(buf, 20, state);
+    _mav_put_uint8_t(buf, 20, initialized);
+    _mav_put_uint8_t(buf, 21, enabled);
     _mav_put_char_array(buf, 0, sensor_name, 20);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
 #else
     mavlink_sensor_state_tm_t packet;
-    packet.state = state;
+    packet.initialized = initialized;
+    packet.enabled = enabled;
     mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
 #endif
@@ -74,21 +80,24 @@ static inline uint16_t mavlink_msg_sensor_state_tm_pack(uint8_t system_id, uint8
  * @param chan The MAVLink channel this message will be sent over
  * @param msg The MAVLink message to compress the data into
  * @param sensor_name  Sensor name
- * @param state  Boolean that represents the init state
+ * @param initialized  Boolean that represents the init state
+ * @param enabled  Boolean that represents the enabled state
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_sensor_state_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   const char *sensor_name,uint8_t state)
+                                   const char *sensor_name,uint8_t initialized,uint8_t enabled)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
-    _mav_put_uint8_t(buf, 20, state);
+    _mav_put_uint8_t(buf, 20, initialized);
+    _mav_put_uint8_t(buf, 21, enabled);
     _mav_put_char_array(buf, 0, sensor_name, 20);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
 #else
     mavlink_sensor_state_tm_t packet;
-    packet.state = state;
+    packet.initialized = initialized;
+    packet.enabled = enabled;
     mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
 #endif
@@ -107,7 +116,7 @@ static inline uint16_t mavlink_msg_sensor_state_tm_pack_chan(uint8_t system_id,
  */
 static inline uint16_t mavlink_msg_sensor_state_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_state_tm_t* sensor_state_tm)
 {
-    return mavlink_msg_sensor_state_tm_pack(system_id, component_id, msg, sensor_state_tm->sensor_name, sensor_state_tm->state);
+    return mavlink_msg_sensor_state_tm_pack(system_id, component_id, msg, sensor_state_tm->sensor_name, sensor_state_tm->initialized, sensor_state_tm->enabled);
 }
 
 /**
@@ -121,7 +130,7 @@ static inline uint16_t mavlink_msg_sensor_state_tm_encode(uint8_t system_id, uin
  */
 static inline uint16_t mavlink_msg_sensor_state_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_state_tm_t* sensor_state_tm)
 {
-    return mavlink_msg_sensor_state_tm_pack_chan(system_id, component_id, chan, msg, sensor_state_tm->sensor_name, sensor_state_tm->state);
+    return mavlink_msg_sensor_state_tm_pack_chan(system_id, component_id, chan, msg, sensor_state_tm->sensor_name, sensor_state_tm->initialized, sensor_state_tm->enabled);
 }
 
 /**
@@ -129,20 +138,23 @@ static inline uint16_t mavlink_msg_sensor_state_tm_encode_chan(uint8_t system_id
  * @param chan MAVLink channel to send the message
  *
  * @param sensor_name  Sensor name
- * @param state  Boolean that represents the init state
+ * @param initialized  Boolean that represents the init state
+ * @param enabled  Boolean that represents the enabled state
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_sensor_state_tm_send(mavlink_channel_t chan, const char *sensor_name, uint8_t state)
+static inline void mavlink_msg_sensor_state_tm_send(mavlink_channel_t chan, const char *sensor_name, uint8_t initialized, uint8_t enabled)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
-    _mav_put_uint8_t(buf, 20, state);
+    _mav_put_uint8_t(buf, 20, initialized);
+    _mav_put_uint8_t(buf, 21, enabled);
     _mav_put_char_array(buf, 0, sensor_name, 20);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
 #else
     mavlink_sensor_state_tm_t packet;
-    packet.state = state;
+    packet.initialized = initialized;
+    packet.enabled = enabled;
     mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
 #endif
@@ -156,7 +168,7 @@ static inline void mavlink_msg_sensor_state_tm_send(mavlink_channel_t chan, cons
 static inline void mavlink_msg_sensor_state_tm_send_struct(mavlink_channel_t chan, const mavlink_sensor_state_tm_t* sensor_state_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_sensor_state_tm_send(chan, sensor_state_tm->sensor_name, sensor_state_tm->state);
+    mavlink_msg_sensor_state_tm_send(chan, sensor_state_tm->sensor_name, sensor_state_tm->initialized, sensor_state_tm->enabled);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, (const char *)sensor_state_tm, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
 #endif
@@ -170,16 +182,18 @@ static inline void mavlink_msg_sensor_state_tm_send_struct(mavlink_channel_t cha
   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_sensor_state_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  const char *sensor_name, uint8_t state)
+static inline void mavlink_msg_sensor_state_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  const char *sensor_name, uint8_t initialized, uint8_t enabled)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
-    _mav_put_uint8_t(buf, 20, state);
+    _mav_put_uint8_t(buf, 20, initialized);
+    _mav_put_uint8_t(buf, 21, enabled);
     _mav_put_char_array(buf, 0, sensor_name, 20);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
 #else
     mavlink_sensor_state_tm_t *packet = (mavlink_sensor_state_tm_t *)msgbuf;
-    packet->state = state;
+    packet->initialized = initialized;
+    packet->enabled = enabled;
     mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, (const char *)packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
 #endif
@@ -202,15 +216,25 @@ static inline uint16_t mavlink_msg_sensor_state_tm_get_sensor_name(const mavlink
 }
 
 /**
- * @brief Get field state from sensor_state_tm message
+ * @brief Get field initialized from sensor_state_tm message
  *
  * @return  Boolean that represents the init state
  */
-static inline uint8_t mavlink_msg_sensor_state_tm_get_state(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_sensor_state_tm_get_initialized(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_uint8_t(msg,  20);
 }
 
+/**
+ * @brief Get field enabled from sensor_state_tm message
+ *
+ * @return  Boolean that represents the enabled state
+ */
+static inline uint8_t mavlink_msg_sensor_state_tm_get_enabled(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  21);
+}
+
 /**
  * @brief Decode a sensor_state_tm message into a struct
  *
@@ -221,7 +245,8 @@ static inline void mavlink_msg_sensor_state_tm_decode(const mavlink_message_t* m
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     mavlink_msg_sensor_state_tm_get_sensor_name(msg, sensor_state_tm->sensor_name);
-    sensor_state_tm->state = mavlink_msg_sensor_state_tm_get_state(msg);
+    sensor_state_tm->initialized = mavlink_msg_sensor_state_tm_get_initialized(msg);
+    sensor_state_tm->enabled = mavlink_msg_sensor_state_tm_get_enabled(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN? msg->len : MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN;
         memset(sensor_state_tm, 0, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_servo_tm.h b/mavlink_lib/lyra/mavlink_msg_servo_tm.h
index 0ffe705d7c4094e1d82b537e2c7977a64b12c86a..22851b9302ca7a4c1d75e87c98afb65a54fd33c9 100644
--- a/mavlink_lib/lyra/mavlink_msg_servo_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_servo_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE SERVO_TM PACKING
 
-#define MAVLINK_MSG_ID_SERVO_TM 112
+#define MAVLINK_MSG_ID_SERVO_TM 113
 
 
 typedef struct __mavlink_servo_tm_t {
@@ -11,17 +11,17 @@ typedef struct __mavlink_servo_tm_t {
 
 #define MAVLINK_MSG_ID_SERVO_TM_LEN 5
 #define MAVLINK_MSG_ID_SERVO_TM_MIN_LEN 5
-#define MAVLINK_MSG_ID_112_LEN 5
-#define MAVLINK_MSG_ID_112_MIN_LEN 5
+#define MAVLINK_MSG_ID_113_LEN 5
+#define MAVLINK_MSG_ID_113_MIN_LEN 5
 
 #define MAVLINK_MSG_ID_SERVO_TM_CRC 87
-#define MAVLINK_MSG_ID_112_CRC 87
+#define MAVLINK_MSG_ID_113_CRC 87
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SERVO_TM { \
-    112, \
+    113, \
     "SERVO_TM", \
     2, \
     {  { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_servo_tm_t, servo_id) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_set_algorithm_tc.h b/mavlink_lib/lyra/mavlink_msg_set_algorithm_tc.h
index 68de47900b54c4ba2dd2d8243250d5a1474d57e2..b9cbbdbd3e049a5339ed0a495302e266af2a2e88 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_algorithm_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_algorithm_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE SET_ALGORITHM_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC 16
+#define MAVLINK_MSG_ID_SET_ALGORITHM_TC 17
 
 
 typedef struct __mavlink_set_algorithm_tc_t {
@@ -10,17 +10,17 @@ typedef struct __mavlink_set_algorithm_tc_t {
 
 #define MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN 1
 #define MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_16_LEN 1
-#define MAVLINK_MSG_ID_16_MIN_LEN 1
+#define MAVLINK_MSG_ID_17_LEN 1
+#define MAVLINK_MSG_ID_17_MIN_LEN 1
 
 #define MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC 181
-#define MAVLINK_MSG_ID_16_CRC 181
+#define MAVLINK_MSG_ID_17_CRC 181
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC { \
-    16, \
+    17, \
     "SET_ALGORITHM_TC", \
     1, \
     {  { "algorithm_number", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_algorithm_tc_t, algorithm_number) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_set_antenna_coordinates_arp_tc.h b/mavlink_lib/lyra/mavlink_msg_set_antenna_coordinates_arp_tc.h
index f24281f4327bf2e569f908cac94a679c428be1c2..27891ad4020ccd2da9d52c04adfe0a64af0a89c0 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_antenna_coordinates_arp_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_antenna_coordinates_arp_tc.h
@@ -1,39 +1,42 @@
 #pragma once
 // MESSAGE SET_ANTENNA_COORDINATES_ARP_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC 170
+#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC 63
 
 
 typedef struct __mavlink_set_antenna_coordinates_arp_tc_t {
  float latitude; /*< [deg] Latitude*/
  float longitude; /*< [deg] Longitude*/
+ float height; /*< [m] Height*/
 } mavlink_set_antenna_coordinates_arp_tc_t;
 
-#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_170_LEN 8
-#define MAVLINK_MSG_ID_170_MIN_LEN 8
+#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN 12
+#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN 12
+#define MAVLINK_MSG_ID_63_LEN 12
+#define MAVLINK_MSG_ID_63_MIN_LEN 12
 
-#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC 202
-#define MAVLINK_MSG_ID_170_CRC 202
+#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC 183
+#define MAVLINK_MSG_ID_63_CRC 183
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC { \
-    170, \
+    63, \
     "SET_ANTENNA_COORDINATES_ARP_TC", \
-    2, \
+    3, \
     {  { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, latitude) }, \
          { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, longitude) }, \
+         { "height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, height) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC { \
     "SET_ANTENNA_COORDINATES_ARP_TC", \
-    2, \
+    3, \
     {  { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, latitude) }, \
          { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, longitude) }, \
+         { "height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, height) }, \
          } \
 }
 #endif
@@ -46,21 +49,24 @@ typedef struct __mavlink_set_antenna_coordinates_arp_tc_t {
  *
  * @param latitude [deg] Latitude
  * @param longitude [deg] Longitude
+ * @param height [m] Height
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               float latitude, float longitude)
+                               float latitude, float longitude, float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN];
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
 #else
     mavlink_set_antenna_coordinates_arp_tc_t packet;
     packet.latitude = latitude;
     packet.longitude = longitude;
+    packet.height = height;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
 #endif
@@ -77,22 +83,25 @@ static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_pack(uint8_t s
  * @param msg The MAVLink message to compress the data into
  * @param latitude [deg] Latitude
  * @param longitude [deg] Longitude
+ * @param height [m] Height
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   float latitude,float longitude)
+                                   float latitude,float longitude,float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN];
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
 #else
     mavlink_set_antenna_coordinates_arp_tc_t packet;
     packet.latitude = latitude;
     packet.longitude = longitude;
+    packet.height = height;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
 #endif
@@ -111,7 +120,7 @@ static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(uint
  */
 static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_antenna_coordinates_arp_tc_t* set_antenna_coordinates_arp_tc)
 {
-    return mavlink_msg_set_antenna_coordinates_arp_tc_pack(system_id, component_id, msg, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude);
+    return mavlink_msg_set_antenna_coordinates_arp_tc_pack(system_id, component_id, msg, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude, set_antenna_coordinates_arp_tc->height);
 }
 
 /**
@@ -125,7 +134,7 @@ static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_encode(uint8_t
  */
 static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_antenna_coordinates_arp_tc_t* set_antenna_coordinates_arp_tc)
 {
-    return mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(system_id, component_id, chan, msg, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude);
+    return mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(system_id, component_id, chan, msg, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude, set_antenna_coordinates_arp_tc->height);
 }
 
 /**
@@ -134,21 +143,24 @@ static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_encode_chan(ui
  *
  * @param latitude [deg] Latitude
  * @param longitude [deg] Longitude
+ * @param height [m] Height
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send(mavlink_channel_t chan, float latitude, float longitude)
+static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send(mavlink_channel_t chan, float latitude, float longitude, float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN];
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
 #else
     mavlink_set_antenna_coordinates_arp_tc_t packet;
     packet.latitude = latitude;
     packet.longitude = longitude;
+    packet.height = height;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
 #endif
@@ -162,7 +174,7 @@ static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send(mavlink_chann
 static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send_struct(mavlink_channel_t chan, const mavlink_set_antenna_coordinates_arp_tc_t* set_antenna_coordinates_arp_tc)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_set_antenna_coordinates_arp_tc_send(chan, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude);
+    mavlink_msg_set_antenna_coordinates_arp_tc_send(chan, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude, set_antenna_coordinates_arp_tc->height);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, (const char *)set_antenna_coordinates_arp_tc, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
 #endif
@@ -176,18 +188,20 @@ static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send_struct(mavlin
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  float latitude, float longitude)
+static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  float latitude, float longitude, float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
 #else
     mavlink_set_antenna_coordinates_arp_tc_t *packet = (mavlink_set_antenna_coordinates_arp_tc_t *)msgbuf;
     packet->latitude = latitude;
     packet->longitude = longitude;
+    packet->height = height;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
 #endif
@@ -219,6 +233,16 @@ static inline float mavlink_msg_set_antenna_coordinates_arp_tc_get_longitude(con
     return _MAV_RETURN_float(msg,  4);
 }
 
+/**
+ * @brief Get field height from set_antenna_coordinates_arp_tc message
+ *
+ * @return [m] Height
+ */
+static inline float mavlink_msg_set_antenna_coordinates_arp_tc_get_height(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  8);
+}
+
 /**
  * @brief Decode a set_antenna_coordinates_arp_tc message into a struct
  *
@@ -230,6 +254,7 @@ static inline void mavlink_msg_set_antenna_coordinates_arp_tc_decode(const mavli
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     set_antenna_coordinates_arp_tc->latitude = mavlink_msg_set_antenna_coordinates_arp_tc_get_latitude(msg);
     set_antenna_coordinates_arp_tc->longitude = mavlink_msg_set_antenna_coordinates_arp_tc_get_longitude(msg);
+    set_antenna_coordinates_arp_tc->height = mavlink_msg_set_antenna_coordinates_arp_tc_get_height(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN;
         memset(set_antenna_coordinates_arp_tc, 0, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_set_atomic_valve_timing_tc.h b/mavlink_lib/lyra/mavlink_msg_set_atomic_valve_timing_tc.h
index 767be290e5f5524ce02c1663f7eaedcd12a5a34f..c43a37eaf41e0d36febf5349e3461b43720d51f5 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_atomic_valve_timing_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_atomic_valve_timing_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE SET_ATOMIC_VALVE_TIMING_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC 17
+#define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC 30
 
 
 typedef struct __mavlink_set_atomic_valve_timing_tc_t {
@@ -11,17 +11,17 @@ typedef struct __mavlink_set_atomic_valve_timing_tc_t {
 
 #define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN 5
 #define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_17_LEN 5
-#define MAVLINK_MSG_ID_17_MIN_LEN 5
+#define MAVLINK_MSG_ID_30_LEN 5
+#define MAVLINK_MSG_ID_30_MIN_LEN 5
 
 #define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC 110
-#define MAVLINK_MSG_ID_17_CRC 110
+#define MAVLINK_MSG_ID_30_CRC 110
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC { \
-    17, \
+    30, \
     "SET_ATOMIC_VALVE_TIMING_TC", \
     2, \
     {  { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_atomic_valve_timing_tc_t, servo_id) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_set_cooling_time_tc.h b/mavlink_lib/lyra/mavlink_msg_set_cooling_time_tc.h
index 9e912d94cde7d2471bf020535417dd8d7f253014..ca49e31c787b7af30cfeed5d599e610a27acc00a 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_cooling_time_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_cooling_time_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE SET_COOLING_TIME_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_COOLING_TIME_TC 24
+#define MAVLINK_MSG_ID_SET_COOLING_TIME_TC 35
 
 
 typedef struct __mavlink_set_cooling_time_tc_t {
@@ -10,17 +10,17 @@ typedef struct __mavlink_set_cooling_time_tc_t {
 
 #define MAVLINK_MSG_ID_SET_COOLING_TIME_TC_LEN 4
 #define MAVLINK_MSG_ID_SET_COOLING_TIME_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_24_LEN 4
-#define MAVLINK_MSG_ID_24_MIN_LEN 4
+#define MAVLINK_MSG_ID_35_LEN 4
+#define MAVLINK_MSG_ID_35_MIN_LEN 4
 
 #define MAVLINK_MSG_ID_SET_COOLING_TIME_TC_CRC 84
-#define MAVLINK_MSG_ID_24_CRC 84
+#define MAVLINK_MSG_ID_35_CRC 84
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_COOLING_TIME_TC { \
-    24, \
+    35, \
     "SET_COOLING_TIME_TC", \
     1, \
     {  { "timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_cooling_time_tc_t, timing) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_set_coordinates_tc.h b/mavlink_lib/lyra/mavlink_msg_set_coordinates_tc.h
index 827f0ec42e8f8ca2cc283732f06ebc1f9a966af0..dd9f914ee780beca86428061f55fa1835510b840 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_coordinates_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_coordinates_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE SET_COORDINATES_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC 12
+#define MAVLINK_MSG_ID_SET_COORDINATES_TC 13
 
 
 typedef struct __mavlink_set_coordinates_tc_t {
@@ -11,17 +11,17 @@ typedef struct __mavlink_set_coordinates_tc_t {
 
 #define MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN 8
 #define MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_12_LEN 8
-#define MAVLINK_MSG_ID_12_MIN_LEN 8
+#define MAVLINK_MSG_ID_13_LEN 8
+#define MAVLINK_MSG_ID_13_MIN_LEN 8
 
 #define MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC 67
-#define MAVLINK_MSG_ID_12_CRC 67
+#define MAVLINK_MSG_ID_13_CRC 67
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC { \
-    12, \
+    13, \
     "SET_COORDINATES_TC", \
     2, \
     {  { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_coordinates_tc_t, latitude) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_set_deployment_altitude_tc.h b/mavlink_lib/lyra/mavlink_msg_set_deployment_altitude_tc.h
index 38c61267d4498fb5f1924eaf8a83b701d0d37677..c8ab791c2fcc1eae10513251650426b28c7756c6 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_deployment_altitude_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_deployment_altitude_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE SET_DEPLOYMENT_ALTITUDE_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC 14
+#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC 15
 
 
 typedef struct __mavlink_set_deployment_altitude_tc_t {
@@ -10,17 +10,17 @@ typedef struct __mavlink_set_deployment_altitude_tc_t {
 
 #define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN 4
 #define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_14_LEN 4
-#define MAVLINK_MSG_ID_14_MIN_LEN 4
+#define MAVLINK_MSG_ID_15_LEN 4
+#define MAVLINK_MSG_ID_15_MIN_LEN 4
 
 #define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC 44
-#define MAVLINK_MSG_ID_14_CRC 44
+#define MAVLINK_MSG_ID_15_CRC 44
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC { \
-    14, \
+    15, \
     "SET_DEPLOYMENT_ALTITUDE_TC", \
     1, \
     {  { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_deployment_altitude_tc_t, dpl_altitude) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_set_ignition_time_tc.h b/mavlink_lib/lyra/mavlink_msg_set_ignition_time_tc.h
index 8ca91d61d9f9331adcf84943b20765cc5b65bc74..43354ed53ff5e0cc6a19f2f26d4c9937b89d7fed 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_ignition_time_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_ignition_time_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE SET_IGNITION_TIME_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC 20
+#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC 33
 
 
 typedef struct __mavlink_set_ignition_time_tc_t {
@@ -10,17 +10,17 @@ typedef struct __mavlink_set_ignition_time_tc_t {
 
 #define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN 4
 #define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_20_LEN 4
-#define MAVLINK_MSG_ID_20_MIN_LEN 4
+#define MAVLINK_MSG_ID_33_LEN 4
+#define MAVLINK_MSG_ID_33_MIN_LEN 4
 
 #define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC 79
-#define MAVLINK_MSG_ID_20_CRC 79
+#define MAVLINK_MSG_ID_33_CRC 79
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC { \
-    20, \
+    33, \
     "SET_IGNITION_TIME_TC", \
     1, \
     {  { "timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_ignition_time_tc_t, timing) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_set_nitrogen_time_tc.h b/mavlink_lib/lyra/mavlink_msg_set_nitrogen_time_tc.h
index c6e48a238a1d9c202f9f218a75208dd8033cb754..49ed042bde281bd1d8828abcf237a66197c7eb7d 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_nitrogen_time_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_nitrogen_time_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE SET_NITROGEN_TIME_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC 23
+#define MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC 34
 
 
 typedef struct __mavlink_set_nitrogen_time_tc_t {
@@ -10,17 +10,17 @@ typedef struct __mavlink_set_nitrogen_time_tc_t {
 
 #define MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_LEN 4
 #define MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_23_LEN 4
-#define MAVLINK_MSG_ID_23_MIN_LEN 4
+#define MAVLINK_MSG_ID_34_LEN 4
+#define MAVLINK_MSG_ID_34_MIN_LEN 4
 
 #define MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_CRC 167
-#define MAVLINK_MSG_ID_23_CRC 167
+#define MAVLINK_MSG_ID_34_CRC 167
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_NITROGEN_TIME_TC { \
-    23, \
+    34, \
     "SET_NITROGEN_TIME_TC", \
     1, \
     {  { "timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_nitrogen_time_tc_t, timing) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_set_orientation_quat_tc.h b/mavlink_lib/lyra/mavlink_msg_set_orientation_quat_tc.h
new file mode 100644
index 0000000000000000000000000000000000000000..fefd5c712166669dfaca1a1ff45aa1581da5ee59
--- /dev/null
+++ b/mavlink_lib/lyra/mavlink_msg_set_orientation_quat_tc.h
@@ -0,0 +1,288 @@
+#pragma once
+// MESSAGE SET_ORIENTATION_QUAT_TC PACKING
+
+#define MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC 12
+
+
+typedef struct __mavlink_set_orientation_quat_tc_t {
+ float quat_x; /*<  Quaternion x component*/
+ float quat_y; /*<  Quaternion y component*/
+ float quat_z; /*<  Quaternion z component*/
+ float quat_w; /*<  Quaternion w component*/
+} mavlink_set_orientation_quat_tc_t;
+
+#define MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN 16
+#define MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN 16
+#define MAVLINK_MSG_ID_12_LEN 16
+#define MAVLINK_MSG_ID_12_MIN_LEN 16
+
+#define MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_CRC 168
+#define MAVLINK_MSG_ID_12_CRC 168
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_SET_ORIENTATION_QUAT_TC { \
+    12, \
+    "SET_ORIENTATION_QUAT_TC", \
+    4, \
+    {  { "quat_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_orientation_quat_tc_t, quat_x) }, \
+         { "quat_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_orientation_quat_tc_t, quat_y) }, \
+         { "quat_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_orientation_quat_tc_t, quat_z) }, \
+         { "quat_w", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_orientation_quat_tc_t, quat_w) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_SET_ORIENTATION_QUAT_TC { \
+    "SET_ORIENTATION_QUAT_TC", \
+    4, \
+    {  { "quat_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_orientation_quat_tc_t, quat_x) }, \
+         { "quat_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_orientation_quat_tc_t, quat_y) }, \
+         { "quat_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_orientation_quat_tc_t, quat_z) }, \
+         { "quat_w", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_orientation_quat_tc_t, quat_w) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a set_orientation_quat_tc message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param quat_x  Quaternion x component
+ * @param quat_y  Quaternion y component
+ * @param quat_z  Quaternion z component
+ * @param quat_w  Quaternion w component
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_orientation_quat_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               float quat_x, float quat_y, float quat_z, float quat_w)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN];
+    _mav_put_float(buf, 0, quat_x);
+    _mav_put_float(buf, 4, quat_y);
+    _mav_put_float(buf, 8, quat_z);
+    _mav_put_float(buf, 12, quat_w);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN);
+#else
+    mavlink_set_orientation_quat_tc_t packet;
+    packet.quat_x = quat_x;
+    packet.quat_y = quat_y;
+    packet.quat_z = quat_z;
+    packet.quat_w = quat_w;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_CRC);
+}
+
+/**
+ * @brief Pack a set_orientation_quat_tc message 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 quat_x  Quaternion x component
+ * @param quat_y  Quaternion y component
+ * @param quat_z  Quaternion z component
+ * @param quat_w  Quaternion w component
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_orientation_quat_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   float quat_x,float quat_y,float quat_z,float quat_w)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN];
+    _mav_put_float(buf, 0, quat_x);
+    _mav_put_float(buf, 4, quat_y);
+    _mav_put_float(buf, 8, quat_z);
+    _mav_put_float(buf, 12, quat_w);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN);
+#else
+    mavlink_set_orientation_quat_tc_t packet;
+    packet.quat_x = quat_x;
+    packet.quat_y = quat_y;
+    packet.quat_z = quat_z;
+    packet.quat_w = quat_w;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_CRC);
+}
+
+/**
+ * @brief Encode a set_orientation_quat_tc 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 set_orientation_quat_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_orientation_quat_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_orientation_quat_tc_t* set_orientation_quat_tc)
+{
+    return mavlink_msg_set_orientation_quat_tc_pack(system_id, component_id, msg, set_orientation_quat_tc->quat_x, set_orientation_quat_tc->quat_y, set_orientation_quat_tc->quat_z, set_orientation_quat_tc->quat_w);
+}
+
+/**
+ * @brief Encode a set_orientation_quat_tc struct 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 set_orientation_quat_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_orientation_quat_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_orientation_quat_tc_t* set_orientation_quat_tc)
+{
+    return mavlink_msg_set_orientation_quat_tc_pack_chan(system_id, component_id, chan, msg, set_orientation_quat_tc->quat_x, set_orientation_quat_tc->quat_y, set_orientation_quat_tc->quat_z, set_orientation_quat_tc->quat_w);
+}
+
+/**
+ * @brief Send a set_orientation_quat_tc message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param quat_x  Quaternion x component
+ * @param quat_y  Quaternion y component
+ * @param quat_z  Quaternion z component
+ * @param quat_w  Quaternion w component
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_orientation_quat_tc_send(mavlink_channel_t chan, float quat_x, float quat_y, float quat_z, float quat_w)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN];
+    _mav_put_float(buf, 0, quat_x);
+    _mav_put_float(buf, 4, quat_y);
+    _mav_put_float(buf, 8, quat_z);
+    _mav_put_float(buf, 12, quat_w);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC, buf, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_CRC);
+#else
+    mavlink_set_orientation_quat_tc_t packet;
+    packet.quat_x = quat_x;
+    packet.quat_y = quat_y;
+    packet.quat_z = quat_z;
+    packet.quat_w = quat_w;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_CRC);
+#endif
+}
+
+/**
+ * @brief Send a set_orientation_quat_tc message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_set_orientation_quat_tc_send_struct(mavlink_channel_t chan, const mavlink_set_orientation_quat_tc_t* set_orientation_quat_tc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_set_orientation_quat_tc_send(chan, set_orientation_quat_tc->quat_x, set_orientation_quat_tc->quat_y, set_orientation_quat_tc->quat_z, set_orientation_quat_tc->quat_w);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC, (const char *)set_orientation_quat_tc, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_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_set_orientation_quat_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  float quat_x, float quat_y, float quat_z, float quat_w)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_float(buf, 0, quat_x);
+    _mav_put_float(buf, 4, quat_y);
+    _mav_put_float(buf, 8, quat_z);
+    _mav_put_float(buf, 12, quat_w);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC, buf, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_CRC);
+#else
+    mavlink_set_orientation_quat_tc_t *packet = (mavlink_set_orientation_quat_tc_t *)msgbuf;
+    packet->quat_x = quat_x;
+    packet->quat_y = quat_y;
+    packet->quat_z = quat_z;
+    packet->quat_w = quat_w;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SET_ORIENTATION_QUAT_TC UNPACKING
+
+
+/**
+ * @brief Get field quat_x from set_orientation_quat_tc message
+ *
+ * @return  Quaternion x component
+ */
+static inline float mavlink_msg_set_orientation_quat_tc_get_quat_x(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  0);
+}
+
+/**
+ * @brief Get field quat_y from set_orientation_quat_tc message
+ *
+ * @return  Quaternion y component
+ */
+static inline float mavlink_msg_set_orientation_quat_tc_get_quat_y(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  4);
+}
+
+/**
+ * @brief Get field quat_z from set_orientation_quat_tc message
+ *
+ * @return  Quaternion z component
+ */
+static inline float mavlink_msg_set_orientation_quat_tc_get_quat_z(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  8);
+}
+
+/**
+ * @brief Get field quat_w from set_orientation_quat_tc message
+ *
+ * @return  Quaternion w component
+ */
+static inline float mavlink_msg_set_orientation_quat_tc_get_quat_w(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  12);
+}
+
+/**
+ * @brief Decode a set_orientation_quat_tc message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_orientation_quat_tc C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_orientation_quat_tc_decode(const mavlink_message_t* msg, mavlink_set_orientation_quat_tc_t* set_orientation_quat_tc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    set_orientation_quat_tc->quat_x = mavlink_msg_set_orientation_quat_tc_get_quat_x(msg);
+    set_orientation_quat_tc->quat_y = mavlink_msg_set_orientation_quat_tc_get_quat_y(msg);
+    set_orientation_quat_tc->quat_z = mavlink_msg_set_orientation_quat_tc_get_quat_z(msg);
+    set_orientation_quat_tc->quat_w = mavlink_msg_set_orientation_quat_tc_get_quat_w(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN;
+        memset(set_orientation_quat_tc, 0, MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_LEN);
+    memcpy(set_orientation_quat_tc, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_rocket_coordinates_arp_tc.h b/mavlink_lib/lyra/mavlink_msg_set_rocket_coordinates_arp_tc.h
index 0cca27cd5973de3fb8d91fc9743ffa980aaf41ba..1956abb73fb473c943ac152b3cc2d62b9994105a 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_rocket_coordinates_arp_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_rocket_coordinates_arp_tc.h
@@ -1,39 +1,42 @@
 #pragma once
 // MESSAGE SET_ROCKET_COORDINATES_ARP_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC 171
+#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC 64
 
 
 typedef struct __mavlink_set_rocket_coordinates_arp_tc_t {
  float latitude; /*< [deg] Latitude*/
  float longitude; /*< [deg] Longitude*/
+ float height; /*< [m] Height*/
 } mavlink_set_rocket_coordinates_arp_tc_t;
 
-#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_171_LEN 8
-#define MAVLINK_MSG_ID_171_MIN_LEN 8
+#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN 12
+#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN 12
+#define MAVLINK_MSG_ID_64_LEN 12
+#define MAVLINK_MSG_ID_64_MIN_LEN 12
 
-#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC 164
-#define MAVLINK_MSG_ID_171_CRC 164
+#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC 220
+#define MAVLINK_MSG_ID_64_CRC 220
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC { \
-    171, \
+    64, \
     "SET_ROCKET_COORDINATES_ARP_TC", \
-    2, \
+    3, \
     {  { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, latitude) }, \
          { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, longitude) }, \
+         { "height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, height) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC { \
     "SET_ROCKET_COORDINATES_ARP_TC", \
-    2, \
+    3, \
     {  { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, latitude) }, \
          { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, longitude) }, \
+         { "height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, height) }, \
          } \
 }
 #endif
@@ -46,21 +49,24 @@ typedef struct __mavlink_set_rocket_coordinates_arp_tc_t {
  *
  * @param latitude [deg] Latitude
  * @param longitude [deg] Longitude
+ * @param height [m] Height
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               float latitude, float longitude)
+                               float latitude, float longitude, float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN];
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
 #else
     mavlink_set_rocket_coordinates_arp_tc_t packet;
     packet.latitude = latitude;
     packet.longitude = longitude;
+    packet.height = height;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
 #endif
@@ -77,22 +83,25 @@ static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_pack(uint8_t sy
  * @param msg The MAVLink message to compress the data into
  * @param latitude [deg] Latitude
  * @param longitude [deg] Longitude
+ * @param height [m] Height
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   float latitude,float longitude)
+                                   float latitude,float longitude,float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN];
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
 #else
     mavlink_set_rocket_coordinates_arp_tc_t packet;
     packet.latitude = latitude;
     packet.longitude = longitude;
+    packet.height = height;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
 #endif
@@ -111,7 +120,7 @@ static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(uint8
  */
 static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_rocket_coordinates_arp_tc_t* set_rocket_coordinates_arp_tc)
 {
-    return mavlink_msg_set_rocket_coordinates_arp_tc_pack(system_id, component_id, msg, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude);
+    return mavlink_msg_set_rocket_coordinates_arp_tc_pack(system_id, component_id, msg, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude, set_rocket_coordinates_arp_tc->height);
 }
 
 /**
@@ -125,7 +134,7 @@ static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_encode(uint8_t
  */
 static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_rocket_coordinates_arp_tc_t* set_rocket_coordinates_arp_tc)
 {
-    return mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(system_id, component_id, chan, msg, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude);
+    return mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(system_id, component_id, chan, msg, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude, set_rocket_coordinates_arp_tc->height);
 }
 
 /**
@@ -134,21 +143,24 @@ static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_encode_chan(uin
  *
  * @param latitude [deg] Latitude
  * @param longitude [deg] Longitude
+ * @param height [m] Height
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send(mavlink_channel_t chan, float latitude, float longitude)
+static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send(mavlink_channel_t chan, float latitude, float longitude, float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN];
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
 #else
     mavlink_set_rocket_coordinates_arp_tc_t packet;
     packet.latitude = latitude;
     packet.longitude = longitude;
+    packet.height = height;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
 #endif
@@ -162,7 +174,7 @@ static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send(mavlink_channe
 static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send_struct(mavlink_channel_t chan, const mavlink_set_rocket_coordinates_arp_tc_t* set_rocket_coordinates_arp_tc)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_set_rocket_coordinates_arp_tc_send(chan, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude);
+    mavlink_msg_set_rocket_coordinates_arp_tc_send(chan, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude, set_rocket_coordinates_arp_tc->height);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, (const char *)set_rocket_coordinates_arp_tc, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
 #endif
@@ -176,18 +188,20 @@ static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send_struct(mavlink
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  float latitude, float longitude)
+static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  float latitude, float longitude, float height)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
     _mav_put_float(buf, 0, latitude);
     _mav_put_float(buf, 4, longitude);
+    _mav_put_float(buf, 8, height);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
 #else
     mavlink_set_rocket_coordinates_arp_tc_t *packet = (mavlink_set_rocket_coordinates_arp_tc_t *)msgbuf;
     packet->latitude = latitude;
     packet->longitude = longitude;
+    packet->height = height;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
 #endif
@@ -219,6 +233,16 @@ static inline float mavlink_msg_set_rocket_coordinates_arp_tc_get_longitude(cons
     return _MAV_RETURN_float(msg,  4);
 }
 
+/**
+ * @brief Get field height from set_rocket_coordinates_arp_tc message
+ *
+ * @return [m] Height
+ */
+static inline float mavlink_msg_set_rocket_coordinates_arp_tc_get_height(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  8);
+}
+
 /**
  * @brief Decode a set_rocket_coordinates_arp_tc message into a struct
  *
@@ -230,6 +254,7 @@ static inline void mavlink_msg_set_rocket_coordinates_arp_tc_decode(const mavlin
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     set_rocket_coordinates_arp_tc->latitude = mavlink_msg_set_rocket_coordinates_arp_tc_get_latitude(msg);
     set_rocket_coordinates_arp_tc->longitude = mavlink_msg_set_rocket_coordinates_arp_tc_get_longitude(msg);
+    set_rocket_coordinates_arp_tc->height = mavlink_msg_set_rocket_coordinates_arp_tc_get_height(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN;
         memset(set_rocket_coordinates_arp_tc, 0, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_set_stepper_angle_tc.h b/mavlink_lib/lyra/mavlink_msg_set_stepper_angle_tc.h
index 332d79f8156a93e4a4952b37d93caecd593a7507..7850e94093721c50cfc9a775568ff7337e785db7 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_stepper_angle_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_stepper_angle_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE SET_STEPPER_ANGLE_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC 21
+#define MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC 60
 
 
 typedef struct __mavlink_set_stepper_angle_tc_t {
@@ -11,17 +11,17 @@ typedef struct __mavlink_set_stepper_angle_tc_t {
 
 #define MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN 5
 #define MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_21_LEN 5
-#define MAVLINK_MSG_ID_21_MIN_LEN 5
+#define MAVLINK_MSG_ID_60_LEN 5
+#define MAVLINK_MSG_ID_60_MIN_LEN 5
 
 #define MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_CRC 180
-#define MAVLINK_MSG_ID_21_CRC 180
+#define MAVLINK_MSG_ID_60_CRC 180
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC { \
-    21, \
+    60, \
     "SET_STEPPER_ANGLE_TC", \
     2, \
     {  { "stepper_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_stepper_angle_tc_t, stepper_id) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_set_stepper_multiplier_tc.h b/mavlink_lib/lyra/mavlink_msg_set_stepper_multiplier_tc.h
new file mode 100644
index 0000000000000000000000000000000000000000..69270ff6d681e252a38e07e7cc0133244bf03d43
--- /dev/null
+++ b/mavlink_lib/lyra/mavlink_msg_set_stepper_multiplier_tc.h
@@ -0,0 +1,238 @@
+#pragma once
+// MESSAGE SET_STEPPER_MULTIPLIER_TC PACKING
+
+#define MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC 62
+
+
+typedef struct __mavlink_set_stepper_multiplier_tc_t {
+ float multiplier; /*<  Multiplier*/
+ uint8_t stepper_id; /*<  A member of the StepperList enum*/
+} mavlink_set_stepper_multiplier_tc_t;
+
+#define MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN 5
+#define MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_MIN_LEN 5
+#define MAVLINK_MSG_ID_62_LEN 5
+#define MAVLINK_MSG_ID_62_MIN_LEN 5
+
+#define MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_CRC 173
+#define MAVLINK_MSG_ID_62_CRC 173
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_SET_STEPPER_MULTIPLIER_TC { \
+    62, \
+    "SET_STEPPER_MULTIPLIER_TC", \
+    2, \
+    {  { "stepper_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_stepper_multiplier_tc_t, stepper_id) }, \
+         { "multiplier", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_stepper_multiplier_tc_t, multiplier) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_SET_STEPPER_MULTIPLIER_TC { \
+    "SET_STEPPER_MULTIPLIER_TC", \
+    2, \
+    {  { "stepper_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_stepper_multiplier_tc_t, stepper_id) }, \
+         { "multiplier", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_stepper_multiplier_tc_t, multiplier) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a set_stepper_multiplier_tc 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 stepper_id  A member of the StepperList enum
+ * @param multiplier  Multiplier
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_stepper_multiplier_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint8_t stepper_id, float multiplier)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN];
+    _mav_put_float(buf, 0, multiplier);
+    _mav_put_uint8_t(buf, 4, stepper_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN);
+#else
+    mavlink_set_stepper_multiplier_tc_t packet;
+    packet.multiplier = multiplier;
+    packet.stepper_id = stepper_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_CRC);
+}
+
+/**
+ * @brief Pack a set_stepper_multiplier_tc 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 stepper_id  A member of the StepperList enum
+ * @param multiplier  Multiplier
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_stepper_multiplier_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint8_t stepper_id,float multiplier)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN];
+    _mav_put_float(buf, 0, multiplier);
+    _mav_put_uint8_t(buf, 4, stepper_id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN);
+#else
+    mavlink_set_stepper_multiplier_tc_t packet;
+    packet.multiplier = multiplier;
+    packet.stepper_id = stepper_id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_CRC);
+}
+
+/**
+ * @brief Encode a set_stepper_multiplier_tc 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 set_stepper_multiplier_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_stepper_multiplier_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_stepper_multiplier_tc_t* set_stepper_multiplier_tc)
+{
+    return mavlink_msg_set_stepper_multiplier_tc_pack(system_id, component_id, msg, set_stepper_multiplier_tc->stepper_id, set_stepper_multiplier_tc->multiplier);
+}
+
+/**
+ * @brief Encode a set_stepper_multiplier_tc 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 set_stepper_multiplier_tc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_stepper_multiplier_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_stepper_multiplier_tc_t* set_stepper_multiplier_tc)
+{
+    return mavlink_msg_set_stepper_multiplier_tc_pack_chan(system_id, component_id, chan, msg, set_stepper_multiplier_tc->stepper_id, set_stepper_multiplier_tc->multiplier);
+}
+
+/**
+ * @brief Send a set_stepper_multiplier_tc message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param stepper_id  A member of the StepperList enum
+ * @param multiplier  Multiplier
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_stepper_multiplier_tc_send(mavlink_channel_t chan, uint8_t stepper_id, float multiplier)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN];
+    _mav_put_float(buf, 0, multiplier);
+    _mav_put_uint8_t(buf, 4, stepper_id);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC, buf, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_CRC);
+#else
+    mavlink_set_stepper_multiplier_tc_t packet;
+    packet.multiplier = multiplier;
+    packet.stepper_id = stepper_id;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_CRC);
+#endif
+}
+
+/**
+ * @brief Send a set_stepper_multiplier_tc message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_set_stepper_multiplier_tc_send_struct(mavlink_channel_t chan, const mavlink_set_stepper_multiplier_tc_t* set_stepper_multiplier_tc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_set_stepper_multiplier_tc_send(chan, set_stepper_multiplier_tc->stepper_id, set_stepper_multiplier_tc->multiplier);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC, (const char *)set_stepper_multiplier_tc, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_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_set_stepper_multiplier_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t stepper_id, float multiplier)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_float(buf, 0, multiplier);
+    _mav_put_uint8_t(buf, 4, stepper_id);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC, buf, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_CRC);
+#else
+    mavlink_set_stepper_multiplier_tc_t *packet = (mavlink_set_stepper_multiplier_tc_t *)msgbuf;
+    packet->multiplier = multiplier;
+    packet->stepper_id = stepper_id;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC, (const char *)packet, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SET_STEPPER_MULTIPLIER_TC UNPACKING
+
+
+/**
+ * @brief Get field stepper_id from set_stepper_multiplier_tc message
+ *
+ * @return  A member of the StepperList enum
+ */
+static inline uint8_t mavlink_msg_set_stepper_multiplier_tc_get_stepper_id(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  4);
+}
+
+/**
+ * @brief Get field multiplier from set_stepper_multiplier_tc message
+ *
+ * @return  Multiplier
+ */
+static inline float mavlink_msg_set_stepper_multiplier_tc_get_multiplier(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  0);
+}
+
+/**
+ * @brief Decode a set_stepper_multiplier_tc message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_stepper_multiplier_tc C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_stepper_multiplier_tc_decode(const mavlink_message_t* msg, mavlink_set_stepper_multiplier_tc_t* set_stepper_multiplier_tc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    set_stepper_multiplier_tc->multiplier = mavlink_msg_set_stepper_multiplier_tc_get_multiplier(msg);
+    set_stepper_multiplier_tc->stepper_id = mavlink_msg_set_stepper_multiplier_tc_get_stepper_id(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN;
+        memset(set_stepper_multiplier_tc, 0, MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_LEN);
+    memcpy(set_stepper_multiplier_tc, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_stepper_steps_tc.h b/mavlink_lib/lyra/mavlink_msg_set_stepper_steps_tc.h
index 5381c0fea9043603df6814431bbe96e1276221da..863b69612c9411bc391b21bb3b5ec31fcf532e5b 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_stepper_steps_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_stepper_steps_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE SET_STEPPER_STEPS_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC 22
+#define MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC 61
 
 
 typedef struct __mavlink_set_stepper_steps_tc_t {
@@ -11,17 +11,17 @@ typedef struct __mavlink_set_stepper_steps_tc_t {
 
 #define MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN 5
 #define MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_22_LEN 5
-#define MAVLINK_MSG_ID_22_MIN_LEN 5
+#define MAVLINK_MSG_ID_61_LEN 5
+#define MAVLINK_MSG_ID_61_MIN_LEN 5
 
 #define MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_CRC 246
-#define MAVLINK_MSG_ID_22_CRC 246
+#define MAVLINK_MSG_ID_61_CRC 246
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC { \
-    22, \
+    61, \
     "SET_STEPPER_STEPS_TC", \
     2, \
     {  { "stepper_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_stepper_steps_tc_t, stepper_id) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_set_target_coordinates_tc.h b/mavlink_lib/lyra/mavlink_msg_set_target_coordinates_tc.h
index 40394b728f76ebb99dfb689a467c28474a457fee..7b7b2cd06cf1404af2933543c3bf45dd00b66072 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_target_coordinates_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_target_coordinates_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE SET_TARGET_COORDINATES_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC 15
+#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC 16
 
 
 typedef struct __mavlink_set_target_coordinates_tc_t {
@@ -11,17 +11,17 @@ typedef struct __mavlink_set_target_coordinates_tc_t {
 
 #define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN 8
 #define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_15_LEN 8
-#define MAVLINK_MSG_ID_15_MIN_LEN 8
+#define MAVLINK_MSG_ID_16_LEN 8
+#define MAVLINK_MSG_ID_16_MIN_LEN 8
 
 #define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC 81
-#define MAVLINK_MSG_ID_15_CRC 81
+#define MAVLINK_MSG_ID_16_CRC 81
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC { \
-    15, \
+    16, \
     "SET_TARGET_COORDINATES_TC", \
     2, \
     {  { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_target_coordinates_tc_t, latitude) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_set_valve_maximum_aperture_tc.h b/mavlink_lib/lyra/mavlink_msg_set_valve_maximum_aperture_tc.h
index 6c13b3e2c6ec3002dd7dbef75785ae68f89ab5aa..a29774f98af65e6c8981a896b79cc4c9bcc42574 100644
--- a/mavlink_lib/lyra/mavlink_msg_set_valve_maximum_aperture_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_set_valve_maximum_aperture_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE SET_VALVE_MAXIMUM_APERTURE_TC PACKING
 
-#define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC 18
+#define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC 31
 
 
 typedef struct __mavlink_set_valve_maximum_aperture_tc_t {
@@ -11,17 +11,17 @@ typedef struct __mavlink_set_valve_maximum_aperture_tc_t {
 
 #define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN 5
 #define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_18_LEN 5
-#define MAVLINK_MSG_ID_18_MIN_LEN 5
+#define MAVLINK_MSG_ID_31_LEN 5
+#define MAVLINK_MSG_ID_31_MIN_LEN 5
 
 #define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC 22
-#define MAVLINK_MSG_ID_18_CRC 22
+#define MAVLINK_MSG_ID_31_CRC 22
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC { \
-    18, \
+    31, \
     "SET_VALVE_MAXIMUM_APERTURE_TC", \
     2, \
     {  { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_valve_maximum_aperture_tc_t, servo_id) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_sys_tm.h b/mavlink_lib/lyra/mavlink_msg_sys_tm.h
index 460e076f05dcf8b83836d80a887f0c77b074c517..4bbfdfedc17a6fc46c7120e2b3ff66956407e676 100644
--- a/mavlink_lib/lyra/mavlink_msg_sys_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_sys_tm.h
@@ -9,18 +9,20 @@ typedef struct __mavlink_sys_tm_t {
  uint8_t logger; /*<  True if the logger started correctly*/
  uint8_t event_broker; /*<  True if the event broker started correctly*/
  uint8_t radio; /*<  True if the radio started correctly*/
- uint8_t pin_observer; /*<  True if the pin observer started correctly*/
  uint8_t sensors; /*<  True if the sensors started correctly*/
- uint8_t board_scheduler; /*<  True if the board scheduler is running*/
+ uint8_t actuators; /*<  True if the sensors started correctly*/
+ uint8_t pin_handler; /*<  True if the pin observer started correctly*/
+ uint8_t can_handler; /*<  True if the can handler started correctly*/
+ uint8_t scheduler; /*<  True if the board scheduler is running*/
 } mavlink_sys_tm_t;
 
-#define MAVLINK_MSG_ID_SYS_TM_LEN 14
-#define MAVLINK_MSG_ID_SYS_TM_MIN_LEN 14
-#define MAVLINK_MSG_ID_200_LEN 14
-#define MAVLINK_MSG_ID_200_MIN_LEN 14
+#define MAVLINK_MSG_ID_SYS_TM_LEN 16
+#define MAVLINK_MSG_ID_SYS_TM_MIN_LEN 16
+#define MAVLINK_MSG_ID_200_LEN 16
+#define MAVLINK_MSG_ID_200_MIN_LEN 16
 
-#define MAVLINK_MSG_ID_SYS_TM_CRC 183
-#define MAVLINK_MSG_ID_200_CRC 183
+#define MAVLINK_MSG_ID_SYS_TM_CRC 48
+#define MAVLINK_MSG_ID_200_CRC 48
 
 
 
@@ -28,27 +30,31 @@ typedef struct __mavlink_sys_tm_t {
 #define MAVLINK_MESSAGE_INFO_SYS_TM { \
     200, \
     "SYS_TM", \
-    7, \
+    9, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sys_tm_t, timestamp) }, \
          { "logger", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_sys_tm_t, logger) }, \
          { "event_broker", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_sys_tm_t, event_broker) }, \
          { "radio", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_sys_tm_t, radio) }, \
-         { "pin_observer", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, pin_observer) }, \
-         { "sensors", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, sensors) }, \
-         { "board_scheduler", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, board_scheduler) }, \
+         { "sensors", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, sensors) }, \
+         { "actuators", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, actuators) }, \
+         { "pin_handler", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, pin_handler) }, \
+         { "can_handler", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_sys_tm_t, can_handler) }, \
+         { "scheduler", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_sys_tm_t, scheduler) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_SYS_TM { \
     "SYS_TM", \
-    7, \
+    9, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sys_tm_t, timestamp) }, \
          { "logger", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_sys_tm_t, logger) }, \
          { "event_broker", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_sys_tm_t, event_broker) }, \
          { "radio", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_sys_tm_t, radio) }, \
-         { "pin_observer", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, pin_observer) }, \
-         { "sensors", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, sensors) }, \
-         { "board_scheduler", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, board_scheduler) }, \
+         { "sensors", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, sensors) }, \
+         { "actuators", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, actuators) }, \
+         { "pin_handler", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, pin_handler) }, \
+         { "can_handler", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_sys_tm_t, can_handler) }, \
+         { "scheduler", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_sys_tm_t, scheduler) }, \
          } \
 }
 #endif
@@ -63,13 +69,15 @@ typedef struct __mavlink_sys_tm_t {
  * @param logger  True if the logger started correctly
  * @param event_broker  True if the event broker started correctly
  * @param radio  True if the radio started correctly
- * @param pin_observer  True if the pin observer started correctly
  * @param sensors  True if the sensors started correctly
- * @param board_scheduler  True if the board scheduler is running
+ * @param actuators  True if the sensors started correctly
+ * @param pin_handler  True if the pin observer started correctly
+ * @param can_handler  True if the can handler started correctly
+ * @param scheduler  True if the board scheduler is running
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_sys_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t pin_observer, uint8_t sensors, uint8_t board_scheduler)
+                               uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t sensors, uint8_t actuators, uint8_t pin_handler, uint8_t can_handler, uint8_t scheduler)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
@@ -77,9 +85,11 @@ static inline uint16_t mavlink_msg_sys_tm_pack(uint8_t system_id, uint8_t compon
     _mav_put_uint8_t(buf, 8, logger);
     _mav_put_uint8_t(buf, 9, event_broker);
     _mav_put_uint8_t(buf, 10, radio);
-    _mav_put_uint8_t(buf, 11, pin_observer);
-    _mav_put_uint8_t(buf, 12, sensors);
-    _mav_put_uint8_t(buf, 13, board_scheduler);
+    _mav_put_uint8_t(buf, 11, sensors);
+    _mav_put_uint8_t(buf, 12, actuators);
+    _mav_put_uint8_t(buf, 13, pin_handler);
+    _mav_put_uint8_t(buf, 14, can_handler);
+    _mav_put_uint8_t(buf, 15, scheduler);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
 #else
@@ -88,9 +98,11 @@ static inline uint16_t mavlink_msg_sys_tm_pack(uint8_t system_id, uint8_t compon
     packet.logger = logger;
     packet.event_broker = event_broker;
     packet.radio = radio;
-    packet.pin_observer = pin_observer;
     packet.sensors = sensors;
-    packet.board_scheduler = board_scheduler;
+    packet.actuators = actuators;
+    packet.pin_handler = pin_handler;
+    packet.can_handler = can_handler;
+    packet.scheduler = scheduler;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
 #endif
@@ -109,14 +121,16 @@ static inline uint16_t mavlink_msg_sys_tm_pack(uint8_t system_id, uint8_t compon
  * @param logger  True if the logger started correctly
  * @param event_broker  True if the event broker started correctly
  * @param radio  True if the radio started correctly
- * @param pin_observer  True if the pin observer started correctly
  * @param sensors  True if the sensors started correctly
- * @param board_scheduler  True if the board scheduler is running
+ * @param actuators  True if the sensors started correctly
+ * @param pin_handler  True if the pin observer started correctly
+ * @param can_handler  True if the can handler started correctly
+ * @param scheduler  True if the board scheduler is running
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_sys_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,uint8_t logger,uint8_t event_broker,uint8_t radio,uint8_t pin_observer,uint8_t sensors,uint8_t board_scheduler)
+                                   uint64_t timestamp,uint8_t logger,uint8_t event_broker,uint8_t radio,uint8_t sensors,uint8_t actuators,uint8_t pin_handler,uint8_t can_handler,uint8_t scheduler)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
@@ -124,9 +138,11 @@ static inline uint16_t mavlink_msg_sys_tm_pack_chan(uint8_t system_id, uint8_t c
     _mav_put_uint8_t(buf, 8, logger);
     _mav_put_uint8_t(buf, 9, event_broker);
     _mav_put_uint8_t(buf, 10, radio);
-    _mav_put_uint8_t(buf, 11, pin_observer);
-    _mav_put_uint8_t(buf, 12, sensors);
-    _mav_put_uint8_t(buf, 13, board_scheduler);
+    _mav_put_uint8_t(buf, 11, sensors);
+    _mav_put_uint8_t(buf, 12, actuators);
+    _mav_put_uint8_t(buf, 13, pin_handler);
+    _mav_put_uint8_t(buf, 14, can_handler);
+    _mav_put_uint8_t(buf, 15, scheduler);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
 #else
@@ -135,9 +151,11 @@ static inline uint16_t mavlink_msg_sys_tm_pack_chan(uint8_t system_id, uint8_t c
     packet.logger = logger;
     packet.event_broker = event_broker;
     packet.radio = radio;
-    packet.pin_observer = pin_observer;
     packet.sensors = sensors;
-    packet.board_scheduler = board_scheduler;
+    packet.actuators = actuators;
+    packet.pin_handler = pin_handler;
+    packet.can_handler = can_handler;
+    packet.scheduler = scheduler;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
 #endif
@@ -156,7 +174,7 @@ static inline uint16_t mavlink_msg_sys_tm_pack_chan(uint8_t system_id, uint8_t c
  */
 static inline uint16_t mavlink_msg_sys_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
 {
-    return mavlink_msg_sys_tm_pack(system_id, component_id, msg, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->pin_observer, sys_tm->sensors, sys_tm->board_scheduler);
+    return mavlink_msg_sys_tm_pack(system_id, component_id, msg, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->sensors, sys_tm->actuators, sys_tm->pin_handler, sys_tm->can_handler, sys_tm->scheduler);
 }
 
 /**
@@ -170,7 +188,7 @@ static inline uint16_t mavlink_msg_sys_tm_encode(uint8_t system_id, uint8_t comp
  */
 static inline uint16_t mavlink_msg_sys_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
 {
-    return mavlink_msg_sys_tm_pack_chan(system_id, component_id, chan, msg, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->pin_observer, sys_tm->sensors, sys_tm->board_scheduler);
+    return mavlink_msg_sys_tm_pack_chan(system_id, component_id, chan, msg, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->sensors, sys_tm->actuators, sys_tm->pin_handler, sys_tm->can_handler, sys_tm->scheduler);
 }
 
 /**
@@ -181,13 +199,15 @@ static inline uint16_t mavlink_msg_sys_tm_encode_chan(uint8_t system_id, uint8_t
  * @param logger  True if the logger started correctly
  * @param event_broker  True if the event broker started correctly
  * @param radio  True if the radio started correctly
- * @param pin_observer  True if the pin observer started correctly
  * @param sensors  True if the sensors started correctly
- * @param board_scheduler  True if the board scheduler is running
+ * @param actuators  True if the sensors started correctly
+ * @param pin_handler  True if the pin observer started correctly
+ * @param can_handler  True if the can handler started correctly
+ * @param scheduler  True if the board scheduler is running
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_sys_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t pin_observer, uint8_t sensors, uint8_t board_scheduler)
+static inline void mavlink_msg_sys_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t sensors, uint8_t actuators, uint8_t pin_handler, uint8_t can_handler, uint8_t scheduler)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
@@ -195,9 +215,11 @@ static inline void mavlink_msg_sys_tm_send(mavlink_channel_t chan, uint64_t time
     _mav_put_uint8_t(buf, 8, logger);
     _mav_put_uint8_t(buf, 9, event_broker);
     _mav_put_uint8_t(buf, 10, radio);
-    _mav_put_uint8_t(buf, 11, pin_observer);
-    _mav_put_uint8_t(buf, 12, sensors);
-    _mav_put_uint8_t(buf, 13, board_scheduler);
+    _mav_put_uint8_t(buf, 11, sensors);
+    _mav_put_uint8_t(buf, 12, actuators);
+    _mav_put_uint8_t(buf, 13, pin_handler);
+    _mav_put_uint8_t(buf, 14, can_handler);
+    _mav_put_uint8_t(buf, 15, scheduler);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, buf, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
 #else
@@ -206,9 +228,11 @@ static inline void mavlink_msg_sys_tm_send(mavlink_channel_t chan, uint64_t time
     packet.logger = logger;
     packet.event_broker = event_broker;
     packet.radio = radio;
-    packet.pin_observer = pin_observer;
     packet.sensors = sensors;
-    packet.board_scheduler = board_scheduler;
+    packet.actuators = actuators;
+    packet.pin_handler = pin_handler;
+    packet.can_handler = can_handler;
+    packet.scheduler = scheduler;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)&packet, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
 #endif
@@ -222,7 +246,7 @@ static inline void mavlink_msg_sys_tm_send(mavlink_channel_t chan, uint64_t time
 static inline void mavlink_msg_sys_tm_send_struct(mavlink_channel_t chan, const mavlink_sys_tm_t* sys_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_sys_tm_send(chan, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->pin_observer, sys_tm->sensors, sys_tm->board_scheduler);
+    mavlink_msg_sys_tm_send(chan, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->sensors, sys_tm->actuators, sys_tm->pin_handler, sys_tm->can_handler, sys_tm->scheduler);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)sys_tm, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
 #endif
@@ -236,7 +260,7 @@ static inline void mavlink_msg_sys_tm_send_struct(mavlink_channel_t chan, const
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_sys_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t pin_observer, uint8_t sensors, uint8_t board_scheduler)
+static inline void mavlink_msg_sys_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t sensors, uint8_t actuators, uint8_t pin_handler, uint8_t can_handler, uint8_t scheduler)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -244,9 +268,11 @@ static inline void mavlink_msg_sys_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     _mav_put_uint8_t(buf, 8, logger);
     _mav_put_uint8_t(buf, 9, event_broker);
     _mav_put_uint8_t(buf, 10, radio);
-    _mav_put_uint8_t(buf, 11, pin_observer);
-    _mav_put_uint8_t(buf, 12, sensors);
-    _mav_put_uint8_t(buf, 13, board_scheduler);
+    _mav_put_uint8_t(buf, 11, sensors);
+    _mav_put_uint8_t(buf, 12, actuators);
+    _mav_put_uint8_t(buf, 13, pin_handler);
+    _mav_put_uint8_t(buf, 14, can_handler);
+    _mav_put_uint8_t(buf, 15, scheduler);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, buf, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
 #else
@@ -255,9 +281,11 @@ static inline void mavlink_msg_sys_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     packet->logger = logger;
     packet->event_broker = event_broker;
     packet->radio = radio;
-    packet->pin_observer = pin_observer;
     packet->sensors = sensors;
-    packet->board_scheduler = board_scheduler;
+    packet->actuators = actuators;
+    packet->pin_handler = pin_handler;
+    packet->can_handler = can_handler;
+    packet->scheduler = scheduler;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)packet, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
 #endif
@@ -310,35 +338,55 @@ static inline uint8_t mavlink_msg_sys_tm_get_radio(const mavlink_message_t* msg)
 }
 
 /**
- * @brief Get field pin_observer from sys_tm message
+ * @brief Get field sensors from sys_tm message
  *
- * @return  True if the pin observer started correctly
+ * @return  True if the sensors started correctly
  */
-static inline uint8_t mavlink_msg_sys_tm_get_pin_observer(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_sys_tm_get_sensors(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_uint8_t(msg,  11);
 }
 
 /**
- * @brief Get field sensors from sys_tm message
+ * @brief Get field actuators from sys_tm message
  *
  * @return  True if the sensors started correctly
  */
-static inline uint8_t mavlink_msg_sys_tm_get_sensors(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_sys_tm_get_actuators(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_uint8_t(msg,  12);
 }
 
 /**
- * @brief Get field board_scheduler from sys_tm message
+ * @brief Get field pin_handler from sys_tm message
  *
- * @return  True if the board scheduler is running
+ * @return  True if the pin observer started correctly
  */
-static inline uint8_t mavlink_msg_sys_tm_get_board_scheduler(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_sys_tm_get_pin_handler(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_uint8_t(msg,  13);
 }
 
+/**
+ * @brief Get field can_handler from sys_tm message
+ *
+ * @return  True if the can handler started correctly
+ */
+static inline uint8_t mavlink_msg_sys_tm_get_can_handler(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  14);
+}
+
+/**
+ * @brief Get field scheduler from sys_tm message
+ *
+ * @return  True if the board scheduler is running
+ */
+static inline uint8_t mavlink_msg_sys_tm_get_scheduler(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  15);
+}
+
 /**
  * @brief Decode a sys_tm message into a struct
  *
@@ -352,9 +400,11 @@ static inline void mavlink_msg_sys_tm_decode(const mavlink_message_t* msg, mavli
     sys_tm->logger = mavlink_msg_sys_tm_get_logger(msg);
     sys_tm->event_broker = mavlink_msg_sys_tm_get_event_broker(msg);
     sys_tm->radio = mavlink_msg_sys_tm_get_radio(msg);
-    sys_tm->pin_observer = mavlink_msg_sys_tm_get_pin_observer(msg);
     sys_tm->sensors = mavlink_msg_sys_tm_get_sensors(msg);
-    sys_tm->board_scheduler = mavlink_msg_sys_tm_get_board_scheduler(msg);
+    sys_tm->actuators = mavlink_msg_sys_tm_get_actuators(msg);
+    sys_tm->pin_handler = mavlink_msg_sys_tm_get_pin_handler(msg);
+    sys_tm->can_handler = mavlink_msg_sys_tm_get_can_handler(msg);
+    sys_tm->scheduler = mavlink_msg_sys_tm_get_scheduler(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_SYS_TM_LEN? msg->len : MAVLINK_MSG_ID_SYS_TM_LEN;
         memset(sys_tm, 0, MAVLINK_MSG_ID_SYS_TM_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_task_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_task_stats_tm.h
index 81727059a4f8f5ed68fc83870afb0b99ab064bba..b30386259c138ea1f350a58f449e55f626c58bb6 100644
--- a/mavlink_lib/lyra/mavlink_msg_task_stats_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_task_stats_tm.h
@@ -6,21 +6,25 @@
 
 typedef struct __mavlink_task_stats_tm_t {
  uint64_t timestamp; /*< [us] When was this logged */
- float task_min; /*<  Task min period*/
- float task_max; /*<  Task max period*/
- float task_mean; /*<  Task mean period*/
- float task_stddev; /*<  Task period std deviation*/
- uint16_t task_period; /*< [ms] Period of the task*/
- uint8_t task_id; /*<  Task ID*/
+ uint32_t task_missed_events; /*<  Number of missed events*/
+ uint32_t task_failed_events; /*<  Number of missed events*/
+ float task_activation_mean; /*<  Task activation mean period*/
+ float task_activation_stddev; /*<  Task activation mean standard deviation*/
+ float task_period_mean; /*<  Task period mean period*/
+ float task_period_stddev; /*<  Task period mean standard deviation*/
+ float task_workload_mean; /*<  Task workload mean period*/
+ float task_workload_stddev; /*<  Task workload mean standard deviation*/
+ uint16_t task_id; /*<  Task ID*/
+ uint16_t task_period; /*< [ns] Period of the task*/
 } mavlink_task_stats_tm_t;
 
-#define MAVLINK_MSG_ID_TASK_STATS_TM_LEN 27
-#define MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN 27
-#define MAVLINK_MSG_ID_204_LEN 27
-#define MAVLINK_MSG_ID_204_MIN_LEN 27
+#define MAVLINK_MSG_ID_TASK_STATS_TM_LEN 44
+#define MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN 44
+#define MAVLINK_MSG_ID_204_LEN 44
+#define MAVLINK_MSG_ID_204_MIN_LEN 44
 
-#define MAVLINK_MSG_ID_TASK_STATS_TM_CRC 133
-#define MAVLINK_MSG_ID_204_CRC 133
+#define MAVLINK_MSG_ID_TASK_STATS_TM_CRC 19
+#define MAVLINK_MSG_ID_204_CRC 19
 
 
 
@@ -28,27 +32,35 @@ typedef struct __mavlink_task_stats_tm_t {
 #define MAVLINK_MESSAGE_INFO_TASK_STATS_TM { \
     204, \
     "TASK_STATS_TM", \
-    7, \
+    11, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_task_stats_tm_t, timestamp) }, \
-         { "task_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_task_stats_tm_t, task_id) }, \
-         { "task_period", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_task_stats_tm_t, task_period) }, \
-         { "task_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_task_stats_tm_t, task_min) }, \
-         { "task_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_task_stats_tm_t, task_max) }, \
-         { "task_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_task_stats_tm_t, task_mean) }, \
-         { "task_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_task_stats_tm_t, task_stddev) }, \
+         { "task_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_task_stats_tm_t, task_id) }, \
+         { "task_period", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_task_stats_tm_t, task_period) }, \
+         { "task_missed_events", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_task_stats_tm_t, task_missed_events) }, \
+         { "task_failed_events", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_task_stats_tm_t, task_failed_events) }, \
+         { "task_activation_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_task_stats_tm_t, task_activation_mean) }, \
+         { "task_activation_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_task_stats_tm_t, task_activation_stddev) }, \
+         { "task_period_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_task_stats_tm_t, task_period_mean) }, \
+         { "task_period_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_task_stats_tm_t, task_period_stddev) }, \
+         { "task_workload_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_task_stats_tm_t, task_workload_mean) }, \
+         { "task_workload_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_task_stats_tm_t, task_workload_stddev) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_TASK_STATS_TM { \
     "TASK_STATS_TM", \
-    7, \
+    11, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_task_stats_tm_t, timestamp) }, \
-         { "task_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_task_stats_tm_t, task_id) }, \
-         { "task_period", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_task_stats_tm_t, task_period) }, \
-         { "task_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_task_stats_tm_t, task_min) }, \
-         { "task_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_task_stats_tm_t, task_max) }, \
-         { "task_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_task_stats_tm_t, task_mean) }, \
-         { "task_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_task_stats_tm_t, task_stddev) }, \
+         { "task_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_task_stats_tm_t, task_id) }, \
+         { "task_period", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_task_stats_tm_t, task_period) }, \
+         { "task_missed_events", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_task_stats_tm_t, task_missed_events) }, \
+         { "task_failed_events", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_task_stats_tm_t, task_failed_events) }, \
+         { "task_activation_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_task_stats_tm_t, task_activation_mean) }, \
+         { "task_activation_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_task_stats_tm_t, task_activation_stddev) }, \
+         { "task_period_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_task_stats_tm_t, task_period_mean) }, \
+         { "task_period_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_task_stats_tm_t, task_period_stddev) }, \
+         { "task_workload_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_task_stats_tm_t, task_workload_mean) }, \
+         { "task_workload_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_task_stats_tm_t, task_workload_stddev) }, \
          } \
 }
 #endif
@@ -61,36 +73,48 @@ typedef struct __mavlink_task_stats_tm_t {
  *
  * @param timestamp [us] When was this logged 
  * @param task_id  Task ID
- * @param task_period [ms] Period of the task
- * @param task_min  Task min period
- * @param task_max  Task max period
- * @param task_mean  Task mean period
- * @param task_stddev  Task period std deviation
+ * @param task_period [ns] Period of the task
+ * @param task_missed_events  Number of missed events
+ * @param task_failed_events  Number of missed events
+ * @param task_activation_mean  Task activation mean period
+ * @param task_activation_stddev  Task activation mean standard deviation
+ * @param task_period_mean  Task period mean period
+ * @param task_period_stddev  Task period mean standard deviation
+ * @param task_workload_mean  Task workload mean period
+ * @param task_workload_stddev  Task workload mean standard deviation
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_task_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, uint8_t task_id, uint16_t task_period, float task_min, float task_max, float task_mean, float task_stddev)
+                               uint64_t timestamp, uint16_t task_id, uint16_t task_period, uint32_t task_missed_events, uint32_t task_failed_events, float task_activation_mean, float task_activation_stddev, float task_period_mean, float task_period_stddev, float task_workload_mean, float task_workload_stddev)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
     _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_float(buf, 8, task_min);
-    _mav_put_float(buf, 12, task_max);
-    _mav_put_float(buf, 16, task_mean);
-    _mav_put_float(buf, 20, task_stddev);
-    _mav_put_uint16_t(buf, 24, task_period);
-    _mav_put_uint8_t(buf, 26, task_id);
+    _mav_put_uint32_t(buf, 8, task_missed_events);
+    _mav_put_uint32_t(buf, 12, task_failed_events);
+    _mav_put_float(buf, 16, task_activation_mean);
+    _mav_put_float(buf, 20, task_activation_stddev);
+    _mav_put_float(buf, 24, task_period_mean);
+    _mav_put_float(buf, 28, task_period_stddev);
+    _mav_put_float(buf, 32, task_workload_mean);
+    _mav_put_float(buf, 36, task_workload_stddev);
+    _mav_put_uint16_t(buf, 40, task_id);
+    _mav_put_uint16_t(buf, 42, task_period);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
 #else
     mavlink_task_stats_tm_t packet;
     packet.timestamp = timestamp;
-    packet.task_min = task_min;
-    packet.task_max = task_max;
-    packet.task_mean = task_mean;
-    packet.task_stddev = task_stddev;
-    packet.task_period = task_period;
+    packet.task_missed_events = task_missed_events;
+    packet.task_failed_events = task_failed_events;
+    packet.task_activation_mean = task_activation_mean;
+    packet.task_activation_stddev = task_activation_stddev;
+    packet.task_period_mean = task_period_mean;
+    packet.task_period_stddev = task_period_stddev;
+    packet.task_workload_mean = task_workload_mean;
+    packet.task_workload_stddev = task_workload_stddev;
     packet.task_id = task_id;
+    packet.task_period = task_period;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
 #endif
@@ -107,37 +131,49 @@ static inline uint16_t mavlink_msg_task_stats_tm_pack(uint8_t system_id, uint8_t
  * @param msg The MAVLink message to compress the data into
  * @param timestamp [us] When was this logged 
  * @param task_id  Task ID
- * @param task_period [ms] Period of the task
- * @param task_min  Task min period
- * @param task_max  Task max period
- * @param task_mean  Task mean period
- * @param task_stddev  Task period std deviation
+ * @param task_period [ns] Period of the task
+ * @param task_missed_events  Number of missed events
+ * @param task_failed_events  Number of missed events
+ * @param task_activation_mean  Task activation mean period
+ * @param task_activation_stddev  Task activation mean standard deviation
+ * @param task_period_mean  Task period mean period
+ * @param task_period_stddev  Task period mean standard deviation
+ * @param task_workload_mean  Task workload mean period
+ * @param task_workload_stddev  Task workload mean standard deviation
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_task_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,uint8_t task_id,uint16_t task_period,float task_min,float task_max,float task_mean,float task_stddev)
+                                   uint64_t timestamp,uint16_t task_id,uint16_t task_period,uint32_t task_missed_events,uint32_t task_failed_events,float task_activation_mean,float task_activation_stddev,float task_period_mean,float task_period_stddev,float task_workload_mean,float task_workload_stddev)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
     _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_float(buf, 8, task_min);
-    _mav_put_float(buf, 12, task_max);
-    _mav_put_float(buf, 16, task_mean);
-    _mav_put_float(buf, 20, task_stddev);
-    _mav_put_uint16_t(buf, 24, task_period);
-    _mav_put_uint8_t(buf, 26, task_id);
+    _mav_put_uint32_t(buf, 8, task_missed_events);
+    _mav_put_uint32_t(buf, 12, task_failed_events);
+    _mav_put_float(buf, 16, task_activation_mean);
+    _mav_put_float(buf, 20, task_activation_stddev);
+    _mav_put_float(buf, 24, task_period_mean);
+    _mav_put_float(buf, 28, task_period_stddev);
+    _mav_put_float(buf, 32, task_workload_mean);
+    _mav_put_float(buf, 36, task_workload_stddev);
+    _mav_put_uint16_t(buf, 40, task_id);
+    _mav_put_uint16_t(buf, 42, task_period);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
 #else
     mavlink_task_stats_tm_t packet;
     packet.timestamp = timestamp;
-    packet.task_min = task_min;
-    packet.task_max = task_max;
-    packet.task_mean = task_mean;
-    packet.task_stddev = task_stddev;
-    packet.task_period = task_period;
+    packet.task_missed_events = task_missed_events;
+    packet.task_failed_events = task_failed_events;
+    packet.task_activation_mean = task_activation_mean;
+    packet.task_activation_stddev = task_activation_stddev;
+    packet.task_period_mean = task_period_mean;
+    packet.task_period_stddev = task_period_stddev;
+    packet.task_workload_mean = task_workload_mean;
+    packet.task_workload_stddev = task_workload_stddev;
     packet.task_id = task_id;
+    packet.task_period = task_period;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
 #endif
@@ -156,7 +192,7 @@ static inline uint16_t mavlink_msg_task_stats_tm_pack_chan(uint8_t system_id, ui
  */
 static inline uint16_t mavlink_msg_task_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_task_stats_tm_t* task_stats_tm)
 {
-    return mavlink_msg_task_stats_tm_pack(system_id, component_id, msg, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_min, task_stats_tm->task_max, task_stats_tm->task_mean, task_stats_tm->task_stddev);
+    return mavlink_msg_task_stats_tm_pack(system_id, component_id, msg, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_missed_events, task_stats_tm->task_failed_events, task_stats_tm->task_activation_mean, task_stats_tm->task_activation_stddev, task_stats_tm->task_period_mean, task_stats_tm->task_period_stddev, task_stats_tm->task_workload_mean, task_stats_tm->task_workload_stddev);
 }
 
 /**
@@ -170,7 +206,7 @@ static inline uint16_t mavlink_msg_task_stats_tm_encode(uint8_t system_id, uint8
  */
 static inline uint16_t mavlink_msg_task_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_task_stats_tm_t* task_stats_tm)
 {
-    return mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, chan, msg, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_min, task_stats_tm->task_max, task_stats_tm->task_mean, task_stats_tm->task_stddev);
+    return mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, chan, msg, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_missed_events, task_stats_tm->task_failed_events, task_stats_tm->task_activation_mean, task_stats_tm->task_activation_stddev, task_stats_tm->task_period_mean, task_stats_tm->task_period_stddev, task_stats_tm->task_workload_mean, task_stats_tm->task_workload_stddev);
 }
 
 /**
@@ -179,36 +215,48 @@ static inline uint16_t mavlink_msg_task_stats_tm_encode_chan(uint8_t system_id,
  *
  * @param timestamp [us] When was this logged 
  * @param task_id  Task ID
- * @param task_period [ms] Period of the task
- * @param task_min  Task min period
- * @param task_max  Task max period
- * @param task_mean  Task mean period
- * @param task_stddev  Task period std deviation
+ * @param task_period [ns] Period of the task
+ * @param task_missed_events  Number of missed events
+ * @param task_failed_events  Number of missed events
+ * @param task_activation_mean  Task activation mean period
+ * @param task_activation_stddev  Task activation mean standard deviation
+ * @param task_period_mean  Task period mean period
+ * @param task_period_stddev  Task period mean standard deviation
+ * @param task_workload_mean  Task workload mean period
+ * @param task_workload_stddev  Task workload mean standard deviation
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_task_stats_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t task_id, uint16_t task_period, float task_min, float task_max, float task_mean, float task_stddev)
+static inline void mavlink_msg_task_stats_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint16_t task_id, uint16_t task_period, uint32_t task_missed_events, uint32_t task_failed_events, float task_activation_mean, float task_activation_stddev, float task_period_mean, float task_period_stddev, float task_workload_mean, float task_workload_stddev)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
     _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_float(buf, 8, task_min);
-    _mav_put_float(buf, 12, task_max);
-    _mav_put_float(buf, 16, task_mean);
-    _mav_put_float(buf, 20, task_stddev);
-    _mav_put_uint16_t(buf, 24, task_period);
-    _mav_put_uint8_t(buf, 26, task_id);
+    _mav_put_uint32_t(buf, 8, task_missed_events);
+    _mav_put_uint32_t(buf, 12, task_failed_events);
+    _mav_put_float(buf, 16, task_activation_mean);
+    _mav_put_float(buf, 20, task_activation_stddev);
+    _mav_put_float(buf, 24, task_period_mean);
+    _mav_put_float(buf, 28, task_period_stddev);
+    _mav_put_float(buf, 32, task_workload_mean);
+    _mav_put_float(buf, 36, task_workload_stddev);
+    _mav_put_uint16_t(buf, 40, task_id);
+    _mav_put_uint16_t(buf, 42, task_period);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, buf, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
 #else
     mavlink_task_stats_tm_t packet;
     packet.timestamp = timestamp;
-    packet.task_min = task_min;
-    packet.task_max = task_max;
-    packet.task_mean = task_mean;
-    packet.task_stddev = task_stddev;
-    packet.task_period = task_period;
+    packet.task_missed_events = task_missed_events;
+    packet.task_failed_events = task_failed_events;
+    packet.task_activation_mean = task_activation_mean;
+    packet.task_activation_stddev = task_activation_stddev;
+    packet.task_period_mean = task_period_mean;
+    packet.task_period_stddev = task_period_stddev;
+    packet.task_workload_mean = task_workload_mean;
+    packet.task_workload_stddev = task_workload_stddev;
     packet.task_id = task_id;
+    packet.task_period = task_period;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
 #endif
@@ -222,7 +270,7 @@ static inline void mavlink_msg_task_stats_tm_send(mavlink_channel_t chan, uint64
 static inline void mavlink_msg_task_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_task_stats_tm_t* task_stats_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_task_stats_tm_send(chan, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_min, task_stats_tm->task_max, task_stats_tm->task_mean, task_stats_tm->task_stddev);
+    mavlink_msg_task_stats_tm_send(chan, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_missed_events, task_stats_tm->task_failed_events, task_stats_tm->task_activation_mean, task_stats_tm->task_activation_stddev, task_stats_tm->task_period_mean, task_stats_tm->task_period_stddev, task_stats_tm->task_workload_mean, task_stats_tm->task_workload_stddev);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)task_stats_tm, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
 #endif
@@ -236,28 +284,36 @@ static inline void mavlink_msg_task_stats_tm_send_struct(mavlink_channel_t chan,
   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_task_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t task_id, uint16_t task_period, float task_min, float task_max, float task_mean, float task_stddev)
+static inline void mavlink_msg_task_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint16_t task_id, uint16_t task_period, uint32_t task_missed_events, uint32_t task_failed_events, float task_activation_mean, float task_activation_stddev, float task_period_mean, float task_period_stddev, float task_workload_mean, float task_workload_stddev)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
     _mav_put_uint64_t(buf, 0, timestamp);
-    _mav_put_float(buf, 8, task_min);
-    _mav_put_float(buf, 12, task_max);
-    _mav_put_float(buf, 16, task_mean);
-    _mav_put_float(buf, 20, task_stddev);
-    _mav_put_uint16_t(buf, 24, task_period);
-    _mav_put_uint8_t(buf, 26, task_id);
+    _mav_put_uint32_t(buf, 8, task_missed_events);
+    _mav_put_uint32_t(buf, 12, task_failed_events);
+    _mav_put_float(buf, 16, task_activation_mean);
+    _mav_put_float(buf, 20, task_activation_stddev);
+    _mav_put_float(buf, 24, task_period_mean);
+    _mav_put_float(buf, 28, task_period_stddev);
+    _mav_put_float(buf, 32, task_workload_mean);
+    _mav_put_float(buf, 36, task_workload_stddev);
+    _mav_put_uint16_t(buf, 40, task_id);
+    _mav_put_uint16_t(buf, 42, task_period);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, buf, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
 #else
     mavlink_task_stats_tm_t *packet = (mavlink_task_stats_tm_t *)msgbuf;
     packet->timestamp = timestamp;
-    packet->task_min = task_min;
-    packet->task_max = task_max;
-    packet->task_mean = task_mean;
-    packet->task_stddev = task_stddev;
-    packet->task_period = task_period;
+    packet->task_missed_events = task_missed_events;
+    packet->task_failed_events = task_failed_events;
+    packet->task_activation_mean = task_activation_mean;
+    packet->task_activation_stddev = task_activation_stddev;
+    packet->task_period_mean = task_period_mean;
+    packet->task_period_stddev = task_period_stddev;
+    packet->task_workload_mean = task_workload_mean;
+    packet->task_workload_stddev = task_workload_stddev;
     packet->task_id = task_id;
+    packet->task_period = task_period;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
 #endif
@@ -284,61 +340,101 @@ static inline uint64_t mavlink_msg_task_stats_tm_get_timestamp(const mavlink_mes
  *
  * @return  Task ID
  */
-static inline uint8_t mavlink_msg_task_stats_tm_get_task_id(const mavlink_message_t* msg)
+static inline uint16_t mavlink_msg_task_stats_tm_get_task_id(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  26);
+    return _MAV_RETURN_uint16_t(msg,  40);
 }
 
 /**
  * @brief Get field task_period from task_stats_tm message
  *
- * @return [ms] Period of the task
+ * @return [ns] Period of the task
  */
 static inline uint16_t mavlink_msg_task_stats_tm_get_task_period(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  24);
+    return _MAV_RETURN_uint16_t(msg,  42);
 }
 
 /**
- * @brief Get field task_min from task_stats_tm message
+ * @brief Get field task_missed_events from task_stats_tm message
  *
- * @return  Task min period
+ * @return  Number of missed events
  */
-static inline float mavlink_msg_task_stats_tm_get_task_min(const mavlink_message_t* msg)
+static inline uint32_t mavlink_msg_task_stats_tm_get_task_missed_events(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  8);
+    return _MAV_RETURN_uint32_t(msg,  8);
 }
 
 /**
- * @brief Get field task_max from task_stats_tm message
+ * @brief Get field task_failed_events from task_stats_tm message
  *
- * @return  Task max period
+ * @return  Number of missed events
  */
-static inline float mavlink_msg_task_stats_tm_get_task_max(const mavlink_message_t* msg)
+static inline uint32_t mavlink_msg_task_stats_tm_get_task_failed_events(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  12);
+    return _MAV_RETURN_uint32_t(msg,  12);
 }
 
 /**
- * @brief Get field task_mean from task_stats_tm message
+ * @brief Get field task_activation_mean from task_stats_tm message
  *
- * @return  Task mean period
+ * @return  Task activation mean period
  */
-static inline float mavlink_msg_task_stats_tm_get_task_mean(const mavlink_message_t* msg)
+static inline float mavlink_msg_task_stats_tm_get_task_activation_mean(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_float(msg,  16);
 }
 
 /**
- * @brief Get field task_stddev from task_stats_tm message
+ * @brief Get field task_activation_stddev from task_stats_tm message
  *
- * @return  Task period std deviation
+ * @return  Task activation mean standard deviation
  */
-static inline float mavlink_msg_task_stats_tm_get_task_stddev(const mavlink_message_t* msg)
+static inline float mavlink_msg_task_stats_tm_get_task_activation_stddev(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_float(msg,  20);
 }
 
+/**
+ * @brief Get field task_period_mean from task_stats_tm message
+ *
+ * @return  Task period mean period
+ */
+static inline float mavlink_msg_task_stats_tm_get_task_period_mean(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  24);
+}
+
+/**
+ * @brief Get field task_period_stddev from task_stats_tm message
+ *
+ * @return  Task period mean standard deviation
+ */
+static inline float mavlink_msg_task_stats_tm_get_task_period_stddev(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  28);
+}
+
+/**
+ * @brief Get field task_workload_mean from task_stats_tm message
+ *
+ * @return  Task workload mean period
+ */
+static inline float mavlink_msg_task_stats_tm_get_task_workload_mean(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  32);
+}
+
+/**
+ * @brief Get field task_workload_stddev from task_stats_tm message
+ *
+ * @return  Task workload mean standard deviation
+ */
+static inline float mavlink_msg_task_stats_tm_get_task_workload_stddev(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  36);
+}
+
 /**
  * @brief Decode a task_stats_tm message into a struct
  *
@@ -349,12 +445,16 @@ static inline void mavlink_msg_task_stats_tm_decode(const mavlink_message_t* msg
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     task_stats_tm->timestamp = mavlink_msg_task_stats_tm_get_timestamp(msg);
-    task_stats_tm->task_min = mavlink_msg_task_stats_tm_get_task_min(msg);
-    task_stats_tm->task_max = mavlink_msg_task_stats_tm_get_task_max(msg);
-    task_stats_tm->task_mean = mavlink_msg_task_stats_tm_get_task_mean(msg);
-    task_stats_tm->task_stddev = mavlink_msg_task_stats_tm_get_task_stddev(msg);
-    task_stats_tm->task_period = mavlink_msg_task_stats_tm_get_task_period(msg);
+    task_stats_tm->task_missed_events = mavlink_msg_task_stats_tm_get_task_missed_events(msg);
+    task_stats_tm->task_failed_events = mavlink_msg_task_stats_tm_get_task_failed_events(msg);
+    task_stats_tm->task_activation_mean = mavlink_msg_task_stats_tm_get_task_activation_mean(msg);
+    task_stats_tm->task_activation_stddev = mavlink_msg_task_stats_tm_get_task_activation_stddev(msg);
+    task_stats_tm->task_period_mean = mavlink_msg_task_stats_tm_get_task_period_mean(msg);
+    task_stats_tm->task_period_stddev = mavlink_msg_task_stats_tm_get_task_period_stddev(msg);
+    task_stats_tm->task_workload_mean = mavlink_msg_task_stats_tm_get_task_workload_mean(msg);
+    task_stats_tm->task_workload_stddev = mavlink_msg_task_stats_tm_get_task_workload_stddev(msg);
     task_stats_tm->task_id = mavlink_msg_task_stats_tm_get_task_id(msg);
+    task_stats_tm->task_period = mavlink_msg_task_stats_tm_get_task_period(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_TASK_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_TASK_STATS_TM_LEN;
         memset(task_stats_tm, 0, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_temp_tm.h b/mavlink_lib/lyra/mavlink_msg_temp_tm.h
index 1334d436975a961e918b50ed4b8d04f058faab3f..2ca27e7f111884943f627673009bb0df4f7cba89 100644
--- a/mavlink_lib/lyra/mavlink_msg_temp_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_temp_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE TEMP_TM PACKING
 
-#define MAVLINK_MSG_ID_TEMP_TM 108
+#define MAVLINK_MSG_ID_TEMP_TM 109
 
 
 typedef struct __mavlink_temp_tm_t {
@@ -12,17 +12,17 @@ typedef struct __mavlink_temp_tm_t {
 
 #define MAVLINK_MSG_ID_TEMP_TM_LEN 32
 #define MAVLINK_MSG_ID_TEMP_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_108_LEN 32
-#define MAVLINK_MSG_ID_108_MIN_LEN 32
+#define MAVLINK_MSG_ID_109_LEN 32
+#define MAVLINK_MSG_ID_109_MIN_LEN 32
 
 #define MAVLINK_MSG_ID_TEMP_TM_CRC 140
-#define MAVLINK_MSG_ID_108_CRC 140
+#define MAVLINK_MSG_ID_109_CRC 140
 
 #define MAVLINK_MSG_TEMP_TM_FIELD_SENSOR_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_TEMP_TM { \
-    108, \
+    109, \
     "TEMP_TM", \
     3, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_temp_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_voltage_tm.h b/mavlink_lib/lyra/mavlink_msg_voltage_tm.h
index 5a391cee271737b01330a5546290d5ba21f3c3a8..ab5547cfbf330fadca17736e9ba1787a539be5cc 100644
--- a/mavlink_lib/lyra/mavlink_msg_voltage_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_voltage_tm.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE VOLTAGE_TM PACKING
 
-#define MAVLINK_MSG_ID_VOLTAGE_TM 106
+#define MAVLINK_MSG_ID_VOLTAGE_TM 107
 
 
 typedef struct __mavlink_voltage_tm_t {
@@ -12,17 +12,17 @@ typedef struct __mavlink_voltage_tm_t {
 
 #define MAVLINK_MSG_ID_VOLTAGE_TM_LEN 32
 #define MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_106_LEN 32
-#define MAVLINK_MSG_ID_106_MIN_LEN 32
+#define MAVLINK_MSG_ID_107_LEN 32
+#define MAVLINK_MSG_ID_107_MIN_LEN 32
 
 #define MAVLINK_MSG_ID_VOLTAGE_TM_CRC 245
-#define MAVLINK_MSG_ID_106_CRC 245
+#define MAVLINK_MSG_ID_107_CRC 245
 
 #define MAVLINK_MSG_VOLTAGE_TM_FIELD_SENSOR_NAME_LEN 20
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_VOLTAGE_TM { \
-    106, \
+    107, \
     "VOLTAGE_TM", \
     3, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_voltage_tm_t, timestamp) }, \
diff --git a/mavlink_lib/lyra/mavlink_msg_wack_tm.h b/mavlink_lib/lyra/mavlink_msg_wack_tm.h
new file mode 100644
index 0000000000000000000000000000000000000000..00837464a535d75aeddf21cedf794f6d0bceb057
--- /dev/null
+++ b/mavlink_lib/lyra/mavlink_msg_wack_tm.h
@@ -0,0 +1,263 @@
+#pragma once
+// MESSAGE WACK_TM PACKING
+
+#define MAVLINK_MSG_ID_WACK_TM 102
+
+
+typedef struct __mavlink_wack_tm_t {
+ uint16_t err_id; /*<  Error core that generated the WACK*/
+ uint8_t recv_msgid; /*<  Message id of the received message*/
+ uint8_t seq_ack; /*<  Sequence number of the received message*/
+} mavlink_wack_tm_t;
+
+#define MAVLINK_MSG_ID_WACK_TM_LEN 4
+#define MAVLINK_MSG_ID_WACK_TM_MIN_LEN 4
+#define MAVLINK_MSG_ID_102_LEN 4
+#define MAVLINK_MSG_ID_102_MIN_LEN 4
+
+#define MAVLINK_MSG_ID_WACK_TM_CRC 51
+#define MAVLINK_MSG_ID_102_CRC 51
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_WACK_TM { \
+    102, \
+    "WACK_TM", \
+    3, \
+    {  { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_wack_tm_t, recv_msgid) }, \
+         { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_wack_tm_t, seq_ack) }, \
+         { "err_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_wack_tm_t, err_id) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_WACK_TM { \
+    "WACK_TM", \
+    3, \
+    {  { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_wack_tm_t, recv_msgid) }, \
+         { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_wack_tm_t, seq_ack) }, \
+         { "err_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_wack_tm_t, err_id) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a wack_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param recv_msgid  Message id of the received message
+ * @param seq_ack  Sequence number of the received message
+ * @param err_id  Error core that generated the WACK
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_wack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint8_t recv_msgid, uint8_t seq_ack, uint16_t err_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_WACK_TM_LEN];
+    _mav_put_uint16_t(buf, 0, err_id);
+    _mav_put_uint8_t(buf, 2, recv_msgid);
+    _mav_put_uint8_t(buf, 3, seq_ack);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WACK_TM_LEN);
+#else
+    mavlink_wack_tm_t packet;
+    packet.err_id = err_id;
+    packet.recv_msgid = recv_msgid;
+    packet.seq_ack = seq_ack;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WACK_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_WACK_TM;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WACK_TM_MIN_LEN, MAVLINK_MSG_ID_WACK_TM_LEN, MAVLINK_MSG_ID_WACK_TM_CRC);
+}
+
+/**
+ * @brief Pack a wack_tm message 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 recv_msgid  Message id of the received message
+ * @param seq_ack  Sequence number of the received message
+ * @param err_id  Error core that generated the WACK
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_wack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint8_t recv_msgid,uint8_t seq_ack,uint16_t err_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_WACK_TM_LEN];
+    _mav_put_uint16_t(buf, 0, err_id);
+    _mav_put_uint8_t(buf, 2, recv_msgid);
+    _mav_put_uint8_t(buf, 3, seq_ack);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WACK_TM_LEN);
+#else
+    mavlink_wack_tm_t packet;
+    packet.err_id = err_id;
+    packet.recv_msgid = recv_msgid;
+    packet.seq_ack = seq_ack;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WACK_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_WACK_TM;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WACK_TM_MIN_LEN, MAVLINK_MSG_ID_WACK_TM_LEN, MAVLINK_MSG_ID_WACK_TM_CRC);
+}
+
+/**
+ * @brief Encode a wack_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 wack_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_wack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wack_tm_t* wack_tm)
+{
+    return mavlink_msg_wack_tm_pack(system_id, component_id, msg, wack_tm->recv_msgid, wack_tm->seq_ack, wack_tm->err_id);
+}
+
+/**
+ * @brief Encode a wack_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 wack_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_wack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wack_tm_t* wack_tm)
+{
+    return mavlink_msg_wack_tm_pack_chan(system_id, component_id, chan, msg, wack_tm->recv_msgid, wack_tm->seq_ack, wack_tm->err_id);
+}
+
+/**
+ * @brief Send a wack_tm message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param recv_msgid  Message id of the received message
+ * @param seq_ack  Sequence number of the received message
+ * @param err_id  Error core that generated the WACK
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_wack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack, uint16_t err_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_WACK_TM_LEN];
+    _mav_put_uint16_t(buf, 0, err_id);
+    _mav_put_uint8_t(buf, 2, recv_msgid);
+    _mav_put_uint8_t(buf, 3, seq_ack);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WACK_TM, buf, MAVLINK_MSG_ID_WACK_TM_MIN_LEN, MAVLINK_MSG_ID_WACK_TM_LEN, MAVLINK_MSG_ID_WACK_TM_CRC);
+#else
+    mavlink_wack_tm_t packet;
+    packet.err_id = err_id;
+    packet.recv_msgid = recv_msgid;
+    packet.seq_ack = seq_ack;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WACK_TM, (const char *)&packet, MAVLINK_MSG_ID_WACK_TM_MIN_LEN, MAVLINK_MSG_ID_WACK_TM_LEN, MAVLINK_MSG_ID_WACK_TM_CRC);
+#endif
+}
+
+/**
+ * @brief Send a wack_tm message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_wack_tm_send_struct(mavlink_channel_t chan, const mavlink_wack_tm_t* wack_tm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_wack_tm_send(chan, wack_tm->recv_msgid, wack_tm->seq_ack, wack_tm->err_id);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WACK_TM, (const char *)wack_tm, MAVLINK_MSG_ID_WACK_TM_MIN_LEN, MAVLINK_MSG_ID_WACK_TM_LEN, MAVLINK_MSG_ID_WACK_TM_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_WACK_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_wack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t recv_msgid, uint8_t seq_ack, uint16_t err_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint16_t(buf, 0, err_id);
+    _mav_put_uint8_t(buf, 2, recv_msgid);
+    _mav_put_uint8_t(buf, 3, seq_ack);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WACK_TM, buf, MAVLINK_MSG_ID_WACK_TM_MIN_LEN, MAVLINK_MSG_ID_WACK_TM_LEN, MAVLINK_MSG_ID_WACK_TM_CRC);
+#else
+    mavlink_wack_tm_t *packet = (mavlink_wack_tm_t *)msgbuf;
+    packet->err_id = err_id;
+    packet->recv_msgid = recv_msgid;
+    packet->seq_ack = seq_ack;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WACK_TM, (const char *)packet, MAVLINK_MSG_ID_WACK_TM_MIN_LEN, MAVLINK_MSG_ID_WACK_TM_LEN, MAVLINK_MSG_ID_WACK_TM_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE WACK_TM UNPACKING
+
+
+/**
+ * @brief Get field recv_msgid from wack_tm message
+ *
+ * @return  Message id of the received message
+ */
+static inline uint8_t mavlink_msg_wack_tm_get_recv_msgid(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  2);
+}
+
+/**
+ * @brief Get field seq_ack from wack_tm message
+ *
+ * @return  Sequence number of the received message
+ */
+static inline uint8_t mavlink_msg_wack_tm_get_seq_ack(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  3);
+}
+
+/**
+ * @brief Get field err_id from wack_tm message
+ *
+ * @return  Error core that generated the WACK
+ */
+static inline uint16_t mavlink_msg_wack_tm_get_err_id(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  0);
+}
+
+/**
+ * @brief Decode a wack_tm message into a struct
+ *
+ * @param msg The message to decode
+ * @param wack_tm C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_wack_tm_decode(const mavlink_message_t* msg, mavlink_wack_tm_t* wack_tm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    wack_tm->err_id = mavlink_msg_wack_tm_get_err_id(msg);
+    wack_tm->recv_msgid = mavlink_msg_wack_tm_get_recv_msgid(msg);
+    wack_tm->seq_ack = mavlink_msg_wack_tm_get_seq_ack(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_WACK_TM_LEN? msg->len : MAVLINK_MSG_ID_WACK_TM_LEN;
+        memset(wack_tm, 0, MAVLINK_MSG_ID_WACK_TM_LEN);
+    memcpy(wack_tm, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/mavlink_lib/lyra/mavlink_msg_wiggle_servo_tc.h b/mavlink_lib/lyra/mavlink_msg_wiggle_servo_tc.h
index b9e333c4ed5bde71c947b204fee64987ed98b2ad..8b127cb2933322c63c571b82f866e87968fa5873 100644
--- a/mavlink_lib/lyra/mavlink_msg_wiggle_servo_tc.h
+++ b/mavlink_lib/lyra/mavlink_msg_wiggle_servo_tc.h
@@ -1,7 +1,7 @@
 #pragma once
 // MESSAGE WIGGLE_SERVO_TC PACKING
 
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC 7
+#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC 8
 
 
 typedef struct __mavlink_wiggle_servo_tc_t {
@@ -10,17 +10,17 @@ typedef struct __mavlink_wiggle_servo_tc_t {
 
 #define MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN 1
 #define MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_7_LEN 1
-#define MAVLINK_MSG_ID_7_MIN_LEN 1
+#define MAVLINK_MSG_ID_8_LEN 1
+#define MAVLINK_MSG_ID_8_MIN_LEN 1
 
 #define MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC 160
-#define MAVLINK_MSG_ID_7_CRC 160
+#define MAVLINK_MSG_ID_8_CRC 160
 
 
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC { \
-    7, \
+    8, \
     "WIGGLE_SERVO_TC", \
     1, \
     {  { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_wiggle_servo_tc_t, servo_id) }, \
diff --git a/mavlink_lib/lyra/testsuite.h b/mavlink_lib/lyra/testsuite.h
index d6a2e616166111b484220071fece2d068833e32d..92f9bf1c989853a6d3530f9c08d5681c8f1f5c61 100644
--- a/mavlink_lib/lyra/testsuite.h
+++ b/mavlink_lib/lyra/testsuite.h
@@ -380,21 +380,21 @@ static void mavlink_test_set_servo_angle_tc(uint8_t system_id, uint8_t component
 #endif
 }
 
-static void mavlink_test_wiggle_servo_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+static void mavlink_test_reset_servo_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
     mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
-        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_WIGGLE_SERVO_TC >= 256) {
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RESET_SERVO_TC >= 256) {
             return;
         }
 #endif
     mavlink_message_t msg;
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
-    mavlink_wiggle_servo_tc_t packet_in = {
+    mavlink_reset_servo_tc_t packet_in = {
         5
     };
-    mavlink_wiggle_servo_tc_t packet1, packet2;
+    mavlink_reset_servo_tc_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.servo_id = packet_in.servo_id;
         
@@ -402,22 +402,22 @@ static void mavlink_test_wiggle_servo_tc(uint8_t system_id, uint8_t component_id
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
         if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
            // cope with extensions
-           memset(MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN);
+           memset(MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN);
         }
 #endif
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_wiggle_servo_tc_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_wiggle_servo_tc_decode(&msg, &packet2);
+    mavlink_msg_reset_servo_tc_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_reset_servo_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_wiggle_servo_tc_pack(system_id, component_id, &msg , packet1.servo_id );
-    mavlink_msg_wiggle_servo_tc_decode(&msg, &packet2);
+    mavlink_msg_reset_servo_tc_pack(system_id, component_id, &msg , packet1.servo_id );
+    mavlink_msg_reset_servo_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_wiggle_servo_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
-    mavlink_msg_wiggle_servo_tc_decode(&msg, &packet2);
+    mavlink_msg_reset_servo_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
+    mavlink_msg_reset_servo_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
@@ -425,35 +425,35 @@ static void mavlink_test_wiggle_servo_tc(uint8_t system_id, uint8_t component_id
         for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
             comm_send_ch(MAVLINK_COMM_0, buffer[i]);
         }
-    mavlink_msg_wiggle_servo_tc_decode(last_msg, &packet2);
+    mavlink_msg_reset_servo_tc_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_wiggle_servo_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
-    mavlink_msg_wiggle_servo_tc_decode(last_msg, &packet2);
+    mavlink_msg_reset_servo_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
+    mavlink_msg_reset_servo_tc_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
 #ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
-    MAVLINK_ASSERT(mavlink_get_message_info_by_name("WIGGLE_SERVO_TC") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_WIGGLE_SERVO_TC) != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("RESET_SERVO_TC") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_RESET_SERVO_TC) != NULL);
 #endif
 }
 
-static void mavlink_test_reset_servo_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+static void mavlink_test_wiggle_servo_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
     mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
-        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RESET_SERVO_TC >= 256) {
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_WIGGLE_SERVO_TC >= 256) {
             return;
         }
 #endif
     mavlink_message_t msg;
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
-    mavlink_reset_servo_tc_t packet_in = {
+    mavlink_wiggle_servo_tc_t packet_in = {
         5
     };
-    mavlink_reset_servo_tc_t packet1, packet2;
+    mavlink_wiggle_servo_tc_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.servo_id = packet_in.servo_id;
         
@@ -461,22 +461,22 @@ static void mavlink_test_reset_servo_tc(uint8_t system_id, uint8_t component_id,
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
         if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
            // cope with extensions
-           memset(MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN);
+           memset(MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN);
         }
 #endif
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_reset_servo_tc_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_reset_servo_tc_decode(&msg, &packet2);
+    mavlink_msg_wiggle_servo_tc_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_wiggle_servo_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_reset_servo_tc_pack(system_id, component_id, &msg , packet1.servo_id );
-    mavlink_msg_reset_servo_tc_decode(&msg, &packet2);
+    mavlink_msg_wiggle_servo_tc_pack(system_id, component_id, &msg , packet1.servo_id );
+    mavlink_msg_wiggle_servo_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_reset_servo_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
-    mavlink_msg_reset_servo_tc_decode(&msg, &packet2);
+    mavlink_msg_wiggle_servo_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
+    mavlink_msg_wiggle_servo_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
@@ -484,17 +484,17 @@ static void mavlink_test_reset_servo_tc(uint8_t system_id, uint8_t component_id,
         for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
             comm_send_ch(MAVLINK_COMM_0, buffer[i]);
         }
-    mavlink_msg_reset_servo_tc_decode(last_msg, &packet2);
+    mavlink_msg_wiggle_servo_tc_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_reset_servo_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
-    mavlink_msg_reset_servo_tc_decode(last_msg, &packet2);
+    mavlink_msg_wiggle_servo_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
+    mavlink_msg_wiggle_servo_tc_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
 #ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
-    MAVLINK_ASSERT(mavlink_get_message_info_by_name("RESET_SERVO_TC") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_RESET_SERVO_TC) != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("WIGGLE_SERVO_TC") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_WIGGLE_SERVO_TC) != NULL);
 #endif
 }
 
@@ -677,6 +677,68 @@ static void mavlink_test_set_orientation_tc(uint8_t system_id, uint8_t component
 #endif
 }
 
+static void mavlink_test_set_orientation_quat_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_set_orientation_quat_tc_t packet_in = {
+        17.0,45.0,73.0,101.0
+    };
+    mavlink_set_orientation_quat_tc_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.quat_x = packet_in.quat_x;
+        packet1.quat_y = packet_in.quat_y;
+        packet1.quat_z = packet_in.quat_z;
+        packet1.quat_w = packet_in.quat_w;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_orientation_quat_tc_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_set_orientation_quat_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_orientation_quat_tc_pack(system_id, component_id, &msg , packet1.quat_x , packet1.quat_y , packet1.quat_z , packet1.quat_w );
+    mavlink_msg_set_orientation_quat_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_orientation_quat_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.quat_x , packet1.quat_y , packet1.quat_z , packet1.quat_w );
+    mavlink_msg_set_orientation_quat_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_set_orientation_quat_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_orientation_quat_tc_send(MAVLINK_COMM_1 , packet1.quat_x , packet1.quat_y , packet1.quat_z , packet1.quat_w );
+    mavlink_msg_set_orientation_quat_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ORIENTATION_QUAT_TC") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ORIENTATION_QUAT_TC) != NULL);
+#endif
+}
+
 static void mavlink_test_set_coordinates_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -1219,6 +1281,124 @@ static void mavlink_test_set_ignition_time_tc(uint8_t system_id, uint8_t compone
 #endif
 }
 
+static void mavlink_test_set_nitrogen_time_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_set_nitrogen_time_tc_t packet_in = {
+        963497464
+    };
+    mavlink_set_nitrogen_time_tc_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.timing = packet_in.timing;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_nitrogen_time_tc_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_set_nitrogen_time_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_nitrogen_time_tc_pack(system_id, component_id, &msg , packet1.timing );
+    mavlink_msg_set_nitrogen_time_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_nitrogen_time_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timing );
+    mavlink_msg_set_nitrogen_time_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_set_nitrogen_time_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_nitrogen_time_tc_send(MAVLINK_COMM_1 , packet1.timing );
+    mavlink_msg_set_nitrogen_time_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_NITROGEN_TIME_TC") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC) != NULL);
+#endif
+}
+
+static void mavlink_test_set_cooling_time_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_COOLING_TIME_TC >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_set_cooling_time_tc_t packet_in = {
+        963497464
+    };
+    mavlink_set_cooling_time_tc_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.timing = packet_in.timing;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_SET_COOLING_TIME_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_COOLING_TIME_TC_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_cooling_time_tc_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_set_cooling_time_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_cooling_time_tc_pack(system_id, component_id, &msg , packet1.timing );
+    mavlink_msg_set_cooling_time_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_cooling_time_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timing );
+    mavlink_msg_set_cooling_time_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_set_cooling_time_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_cooling_time_tc_send(MAVLINK_COMM_1 , packet1.timing );
+    mavlink_msg_set_cooling_time_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_COOLING_TIME_TC") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_COOLING_TIME_TC) != NULL);
+#endif
+}
+
 static void mavlink_test_set_stepper_angle_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -1339,44 +1519,45 @@ static void mavlink_test_set_stepper_steps_tc(uint8_t system_id, uint8_t compone
 #endif
 }
 
-static void mavlink_test_set_nitrogen_time_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+static void mavlink_test_set_stepper_multiplier_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
     mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
-        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC >= 256) {
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC >= 256) {
             return;
         }
 #endif
     mavlink_message_t msg;
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
-    mavlink_set_nitrogen_time_tc_t packet_in = {
-        963497464
+    mavlink_set_stepper_multiplier_tc_t packet_in = {
+        17.0,17
     };
-    mavlink_set_nitrogen_time_tc_t packet1, packet2;
+    mavlink_set_stepper_multiplier_tc_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
-        packet1.timing = packet_in.timing;
+        packet1.multiplier = packet_in.multiplier;
+        packet1.stepper_id = packet_in.stepper_id;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
         if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
            // cope with extensions
-           memset(MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC_MIN_LEN);
+           memset(MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC_MIN_LEN);
         }
 #endif
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_nitrogen_time_tc_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_set_nitrogen_time_tc_decode(&msg, &packet2);
+    mavlink_msg_set_stepper_multiplier_tc_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_set_stepper_multiplier_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_nitrogen_time_tc_pack(system_id, component_id, &msg , packet1.timing );
-    mavlink_msg_set_nitrogen_time_tc_decode(&msg, &packet2);
+    mavlink_msg_set_stepper_multiplier_tc_pack(system_id, component_id, &msg , packet1.stepper_id , packet1.multiplier );
+    mavlink_msg_set_stepper_multiplier_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_nitrogen_time_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timing );
-    mavlink_msg_set_nitrogen_time_tc_decode(&msg, &packet2);
+    mavlink_msg_set_stepper_multiplier_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.stepper_id , packet1.multiplier );
+    mavlink_msg_set_stepper_multiplier_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
@@ -1384,58 +1565,60 @@ static void mavlink_test_set_nitrogen_time_tc(uint8_t system_id, uint8_t compone
         for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
             comm_send_ch(MAVLINK_COMM_0, buffer[i]);
         }
-    mavlink_msg_set_nitrogen_time_tc_decode(last_msg, &packet2);
+    mavlink_msg_set_stepper_multiplier_tc_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_nitrogen_time_tc_send(MAVLINK_COMM_1 , packet1.timing );
-    mavlink_msg_set_nitrogen_time_tc_decode(last_msg, &packet2);
+    mavlink_msg_set_stepper_multiplier_tc_send(MAVLINK_COMM_1 , packet1.stepper_id , packet1.multiplier );
+    mavlink_msg_set_stepper_multiplier_tc_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
 #ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
-    MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_NITROGEN_TIME_TC") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC) != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_STEPPER_MULTIPLIER_TC") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_STEPPER_MULTIPLIER_TC) != NULL);
 #endif
 }
 
-static void mavlink_test_set_cooling_time_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+static void mavlink_test_set_antenna_coordinates_arp_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
     mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
-        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_COOLING_TIME_TC >= 256) {
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC >= 256) {
             return;
         }
 #endif
     mavlink_message_t msg;
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
-    mavlink_set_cooling_time_tc_t packet_in = {
-        963497464
+    mavlink_set_antenna_coordinates_arp_tc_t packet_in = {
+        17.0,45.0,73.0
     };
-    mavlink_set_cooling_time_tc_t packet1, packet2;
+    mavlink_set_antenna_coordinates_arp_tc_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
-        packet1.timing = packet_in.timing;
+        packet1.latitude = packet_in.latitude;
+        packet1.longitude = packet_in.longitude;
+        packet1.height = packet_in.height;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
         if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
            // cope with extensions
-           memset(MAVLINK_MSG_ID_SET_COOLING_TIME_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_COOLING_TIME_TC_MIN_LEN);
+           memset(MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN);
         }
 #endif
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_cooling_time_tc_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_set_cooling_time_tc_decode(&msg, &packet2);
+    mavlink_msg_set_antenna_coordinates_arp_tc_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_set_antenna_coordinates_arp_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_cooling_time_tc_pack(system_id, component_id, &msg , packet1.timing );
-    mavlink_msg_set_cooling_time_tc_decode(&msg, &packet2);
+    mavlink_msg_set_antenna_coordinates_arp_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.height );
+    mavlink_msg_set_antenna_coordinates_arp_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_cooling_time_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timing );
-    mavlink_msg_set_cooling_time_tc_decode(&msg, &packet2);
+    mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.height );
+    mavlink_msg_set_antenna_coordinates_arp_tc_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
@@ -1443,17 +1626,137 @@ static void mavlink_test_set_cooling_time_tc(uint8_t system_id, uint8_t componen
         for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
             comm_send_ch(MAVLINK_COMM_0, buffer[i]);
         }
-    mavlink_msg_set_cooling_time_tc_decode(last_msg, &packet2);
+    mavlink_msg_set_antenna_coordinates_arp_tc_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_cooling_time_tc_send(MAVLINK_COMM_1 , packet1.timing );
-    mavlink_msg_set_cooling_time_tc_decode(last_msg, &packet2);
+    mavlink_msg_set_antenna_coordinates_arp_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude , packet1.height );
+    mavlink_msg_set_antenna_coordinates_arp_tc_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
 #ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
-    MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_COOLING_TIME_TC") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_COOLING_TIME_TC) != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ANTENNA_COORDINATES_ARP_TC") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC) != NULL);
+#endif
+}
+
+static void mavlink_test_set_rocket_coordinates_arp_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_set_rocket_coordinates_arp_tc_t packet_in = {
+        17.0,45.0,73.0
+    };
+    mavlink_set_rocket_coordinates_arp_tc_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.latitude = packet_in.latitude;
+        packet1.longitude = packet_in.longitude;
+        packet1.height = packet_in.height;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_rocket_coordinates_arp_tc_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_set_rocket_coordinates_arp_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_rocket_coordinates_arp_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.height );
+    mavlink_msg_set_rocket_coordinates_arp_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.height );
+    mavlink_msg_set_rocket_coordinates_arp_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_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_set_rocket_coordinates_arp_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_set_rocket_coordinates_arp_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude , packet1.height );
+    mavlink_msg_set_rocket_coordinates_arp_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ROCKET_COORDINATES_ARP_TC") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC) != NULL);
+#endif
+}
+
+static void mavlink_test_arp_command_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ARP_COMMAND_TC >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_arp_command_tc_t packet_in = {
+        5
+    };
+    mavlink_arp_command_tc_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.command_id = packet_in.command_id;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_arp_command_tc_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_arp_command_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_arp_command_tc_pack(system_id, component_id, &msg , packet1.command_id );
+    mavlink_msg_arp_command_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_arp_command_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command_id );
+    mavlink_msg_arp_command_tc_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_arp_command_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_arp_command_tc_send(MAVLINK_COMM_1 , packet1.command_id );
+    mavlink_msg_arp_command_tc_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("ARP_COMMAND_TC") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ARP_COMMAND_TC) != NULL);
 #endif
 }
 
@@ -1529,10 +1832,11 @@ static void mavlink_test_nack_tm(uint8_t system_id, uint8_t component_id, mavlin
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_nack_tm_t packet_in = {
-        5,72
+        17235,139,206
     };
     mavlink_nack_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
+        packet1.err_id = packet_in.err_id;
         packet1.recv_msgid = packet_in.recv_msgid;
         packet1.seq_ack = packet_in.seq_ack;
         
@@ -1549,12 +1853,12 @@ static void mavlink_test_nack_tm(uint8_t system_id, uint8_t component_id, mavlin
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_nack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack );
+    mavlink_msg_nack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack , packet1.err_id );
     mavlink_msg_nack_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_nack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack );
+    mavlink_msg_nack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack , packet1.err_id );
     mavlink_msg_nack_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -1567,7 +1871,7 @@ static void mavlink_test_nack_tm(uint8_t system_id, uint8_t component_id, mavlin
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_nack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack );
+    mavlink_msg_nack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack , packet1.err_id );
     mavlink_msg_nack_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -1577,6 +1881,67 @@ static void mavlink_test_nack_tm(uint8_t system_id, uint8_t component_id, mavlin
 #endif
 }
 
+static void mavlink_test_wack_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_WACK_TM >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_wack_tm_t packet_in = {
+        17235,139,206
+    };
+    mavlink_wack_tm_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.err_id = packet_in.err_id;
+        packet1.recv_msgid = packet_in.recv_msgid;
+        packet1.seq_ack = packet_in.seq_ack;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_WACK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WACK_TM_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_wack_tm_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_wack_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_wack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack , packet1.err_id );
+    mavlink_msg_wack_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_wack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack , packet1.err_id );
+    mavlink_msg_wack_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_wack_tm_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_wack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack , packet1.err_id );
+    mavlink_msg_wack_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("WACK_TM") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_WACK_TM) != NULL);
+#endif
+}
+
 static void mavlink_test_gps_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -2168,11 +2533,12 @@ static void mavlink_test_sensor_state_tm(uint8_t system_id, uint8_t component_id
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_sensor_state_tm_t packet_in = {
-        "ABCDEFGHIJKLMNOPQRS",65
+        "ABCDEFGHIJKLMNOPQRS",65,132
     };
     mavlink_sensor_state_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
-        packet1.state = packet_in.state;
+        packet1.initialized = packet_in.initialized;
+        packet1.enabled = packet_in.enabled;
         
         mav_array_memcpy(packet1.sensor_name, packet_in.sensor_name, sizeof(char)*20);
         
@@ -2188,12 +2554,12 @@ static void mavlink_test_sensor_state_tm(uint8_t system_id, uint8_t component_id
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_sensor_state_tm_pack(system_id, component_id, &msg , packet1.sensor_name , packet1.state );
+    mavlink_msg_sensor_state_tm_pack(system_id, component_id, &msg , packet1.sensor_name , packet1.initialized , packet1.enabled );
     mavlink_msg_sensor_state_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_sensor_state_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.sensor_name , packet1.state );
+    mavlink_msg_sensor_state_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.sensor_name , packet1.initialized , packet1.enabled );
     mavlink_msg_sensor_state_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2206,7 +2572,7 @@ static void mavlink_test_sensor_state_tm(uint8_t system_id, uint8_t component_id
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_sensor_state_tm_send(MAVLINK_COMM_1 , packet1.sensor_name , packet1.state );
+    mavlink_msg_sensor_state_tm_send(MAVLINK_COMM_1 , packet1.sensor_name , packet1.initialized , packet1.enabled );
     mavlink_msg_sensor_state_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2344,329 +2710,42 @@ static void mavlink_test_registry_float_tm(uint8_t system_id, uint8_t component_
 #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_REGISTRY_FLOAT_TM >= 256) {
-            return;
-        }
-#endif
-    mavlink_message_t msg;
-        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
-        uint16_t i;
-    mavlink_registry_float_tm_t packet_in = {
-        93372036854775807ULL,963497880,101.0,"QRSTUVWXYZABCDEFGHI"
-    };
-    mavlink_registry_float_tm_t packet1, packet2;
-        memset(&packet1, 0, sizeof(packet1));
-        packet1.timestamp = packet_in.timestamp;
-        packet1.key_id = packet_in.key_id;
-        packet1.value = packet_in.value;
-        
-        mav_array_memcpy(packet1.key_name, packet_in.key_name, sizeof(char)*20);
-        
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
-        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
-           // cope with extensions
-           memset(MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_MIN_LEN);
-        }
-#endif
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_registry_float_tm_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_registry_float_tm_decode(&msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_registry_float_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.value );
-    mavlink_msg_registry_float_tm_decode(&msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_registry_float_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.value );
-    mavlink_msg_registry_float_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_registry_float_tm_decode(last_msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-        
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_registry_float_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.value );
-    mavlink_msg_registry_float_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("REGISTRY_FLOAT_TM") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_REGISTRY_FLOAT_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_registry_int_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_REGISTRY_INT_TM >= 256) {
-            return;
-        }
-#endif
-    mavlink_message_t msg;
-        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
-        uint16_t i;
-    mavlink_registry_int_tm_t packet_in = {
-        93372036854775807ULL,963497880,963498088,"QRSTUVWXYZABCDEFGHI"
-    };
-    mavlink_registry_int_tm_t packet1, packet2;
-        memset(&packet1, 0, sizeof(packet1));
-        packet1.timestamp = packet_in.timestamp;
-        packet1.key_id = packet_in.key_id;
-        packet1.value = packet_in.value;
-        
-        mav_array_memcpy(packet1.key_name, packet_in.key_name, sizeof(char)*20);
-        
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
-        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
-           // cope with extensions
-           memset(MAVLINK_MSG_ID_REGISTRY_INT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_REGISTRY_INT_TM_MIN_LEN);
-        }
-#endif
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_registry_int_tm_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_registry_int_tm_decode(&msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_registry_int_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.value );
-    mavlink_msg_registry_int_tm_decode(&msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_registry_int_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.value );
-    mavlink_msg_registry_int_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_registry_int_tm_decode(last_msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-        
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_registry_int_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.value );
-    mavlink_msg_registry_int_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("REGISTRY_INT_TM") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_REGISTRY_INT_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_registry_coord_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_REGISTRY_COORD_TM >= 256) {
-            return;
-        }
-#endif
-    mavlink_message_t msg;
-        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
-        uint16_t i;
-    mavlink_registry_coord_tm_t packet_in = {
-        93372036854775807ULL,963497880,101.0,129.0,"UVWXYZABCDEFGHIJKLM"
-    };
-    mavlink_registry_coord_tm_t packet1, packet2;
-        memset(&packet1, 0, sizeof(packet1));
-        packet1.timestamp = packet_in.timestamp;
-        packet1.key_id = packet_in.key_id;
-        packet1.latitude = packet_in.latitude;
-        packet1.longitude = packet_in.longitude;
-        
-        mav_array_memcpy(packet1.key_name, packet_in.key_name, sizeof(char)*20);
-        
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
-        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
-           // cope with extensions
-           memset(MAVLINK_MSG_ID_REGISTRY_COORD_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_REGISTRY_COORD_TM_MIN_LEN);
-        }
-#endif
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_registry_coord_tm_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_registry_coord_tm_decode(&msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_registry_coord_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.latitude , packet1.longitude );
-    mavlink_msg_registry_coord_tm_decode(&msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_registry_coord_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.latitude , packet1.longitude );
-    mavlink_msg_registry_coord_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_registry_coord_tm_decode(last_msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-        
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_registry_coord_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.latitude , packet1.longitude );
-    mavlink_msg_registry_coord_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("REGISTRY_COORD_TM") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_REGISTRY_COORD_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_receiver_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_RECEIVER_TM >= 256) {
-            return;
-        }
-#endif
-    mavlink_message_t msg;
-        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
-        uint16_t i;
-    mavlink_receiver_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,18691,18795,18899,19003,19107,19211,19315,19419,19523,19627,149,216,27,94
-    };
-    mavlink_receiver_tm_t packet1, packet2;
-        memset(&packet1, 0, sizeof(packet1));
-        packet1.timestamp = packet_in.timestamp;
-        packet1.main_rx_rssi = packet_in.main_rx_rssi;
-        packet1.main_rx_fei = packet_in.main_rx_fei;
-        packet1.payload_rx_rssi = packet_in.payload_rx_rssi;
-        packet1.payload_rx_fei = packet_in.payload_rx_fei;
-        packet1.battery_voltage = packet_in.battery_voltage;
-        packet1.main_packet_tx_error_count = packet_in.main_packet_tx_error_count;
-        packet1.main_tx_bitrate = packet_in.main_tx_bitrate;
-        packet1.main_packet_rx_success_count = packet_in.main_packet_rx_success_count;
-        packet1.main_packet_rx_drop_count = packet_in.main_packet_rx_drop_count;
-        packet1.main_rx_bitrate = packet_in.main_rx_bitrate;
-        packet1.payload_packet_tx_error_count = packet_in.payload_packet_tx_error_count;
-        packet1.payload_tx_bitrate = packet_in.payload_tx_bitrate;
-        packet1.payload_packet_rx_success_count = packet_in.payload_packet_rx_success_count;
-        packet1.payload_packet_rx_drop_count = packet_in.payload_packet_rx_drop_count;
-        packet1.payload_rx_bitrate = packet_in.payload_rx_bitrate;
-        packet1.main_radio_present = packet_in.main_radio_present;
-        packet1.payload_radio_present = packet_in.payload_radio_present;
-        packet1.ethernet_present = packet_in.ethernet_present;
-        packet1.ethernet_status = packet_in.ethernet_status;
-        
-        
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
-        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
-           // cope with extensions
-           memset(MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN);
-        }
-#endif
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_receiver_tm_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_receiver_tm_decode(&msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_receiver_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
-    mavlink_msg_receiver_tm_decode(&msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_receiver_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
-    mavlink_msg_receiver_tm_decode(&msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-        memset(&packet2, 0, sizeof(packet2));
-        mavlink_msg_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_receiver_tm_decode(last_msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-        
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_receiver_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
-    mavlink_msg_receiver_tm_decode(last_msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
-    MAVLINK_ASSERT(mavlink_get_message_info_by_name("RECEIVER_TM") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_RECEIVER_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_arp_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_ARP_TM >= 256) {
-            return;
-        }
-#endif
-    mavlink_message_t msg;
-        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
-        uint16_t i;
-    mavlink_arp_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,20979,21083,21187,21291,21395,123,190,1,68
-    };
-    mavlink_arp_tm_t packet1, packet2;
-        memset(&packet1, 0, sizeof(packet1));
-        packet1.timestamp = packet_in.timestamp;
-        packet1.yaw = packet_in.yaw;
-        packet1.pitch = packet_in.pitch;
-        packet1.roll = packet_in.roll;
-        packet1.target_yaw = packet_in.target_yaw;
-        packet1.target_pitch = packet_in.target_pitch;
-        packet1.stepperX_pos = packet_in.stepperX_pos;
-        packet1.stepperX_delta = packet_in.stepperX_delta;
-        packet1.stepperX_speed = packet_in.stepperX_speed;
-        packet1.stepperY_pos = packet_in.stepperY_pos;
-        packet1.stepperY_delta = packet_in.stepperY_delta;
-        packet1.stepperY_speed = packet_in.stepperY_speed;
-        packet1.gps_latitude = packet_in.gps_latitude;
-        packet1.gps_longitude = packet_in.gps_longitude;
-        packet1.gps_height = packet_in.gps_height;
-        packet1.main_rx_rssi = packet_in.main_rx_rssi;
-        packet1.battery_voltage = packet_in.battery_voltage;
-        packet1.main_packet_tx_error_count = packet_in.main_packet_tx_error_count;
-        packet1.main_tx_bitrate = packet_in.main_tx_bitrate;
-        packet1.main_packet_rx_success_count = packet_in.main_packet_rx_success_count;
-        packet1.main_packet_rx_drop_count = packet_in.main_packet_rx_drop_count;
-        packet1.main_rx_bitrate = packet_in.main_rx_bitrate;
-        packet1.gps_fix = packet_in.gps_fix;
-        packet1.main_radio_present = packet_in.main_radio_present;
-        packet1.ethernet_present = packet_in.ethernet_present;
-        packet1.ethernet_status = packet_in.ethernet_status;
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_registry_float_tm_t packet_in = {
+        93372036854775807ULL,963497880,101.0,"QRSTUVWXYZABCDEFGHI"
+    };
+    mavlink_registry_float_tm_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.timestamp = packet_in.timestamp;
+        packet1.key_id = packet_in.key_id;
+        packet1.value = packet_in.value;
         
+        mav_array_memcpy(packet1.key_name, packet_in.key_name, sizeof(char)*20);
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
         if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
            // cope with extensions
-           memset(MAVLINK_MSG_ID_ARP_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ARP_TM_MIN_LEN);
+           memset(MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_REGISTRY_FLOAT_TM_MIN_LEN);
         }
 #endif
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_arp_tm_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_arp_tm_decode(&msg, &packet2);
+    mavlink_msg_registry_float_tm_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_registry_float_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_arp_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
-    mavlink_msg_arp_tm_decode(&msg, &packet2);
+    mavlink_msg_registry_float_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.value );
+    mavlink_msg_registry_float_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_arp_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
-    mavlink_msg_arp_tm_decode(&msg, &packet2);
+    mavlink_msg_registry_float_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.value );
+    mavlink_msg_registry_float_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
@@ -2674,59 +2753,61 @@ static void mavlink_test_arp_tm(uint8_t system_id, uint8_t component_id, mavlink
         for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
             comm_send_ch(MAVLINK_COMM_0, buffer[i]);
         }
-    mavlink_msg_arp_tm_decode(last_msg, &packet2);
+    mavlink_msg_registry_float_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_arp_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
-    mavlink_msg_arp_tm_decode(last_msg, &packet2);
+    mavlink_msg_registry_float_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.value );
+    mavlink_msg_registry_float_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("ARP_TM") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ARP_TM) != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("REGISTRY_FLOAT_TM") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_REGISTRY_FLOAT_TM) != NULL);
 #endif
 }
 
-static void mavlink_test_set_antenna_coordinates_arp_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+static void mavlink_test_registry_int_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_SET_ANTENNA_COORDINATES_ARP_TC >= 256) {
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_REGISTRY_INT_TM >= 256) {
             return;
         }
 #endif
     mavlink_message_t msg;
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
-    mavlink_set_antenna_coordinates_arp_tc_t packet_in = {
-        17.0,45.0
+    mavlink_registry_int_tm_t packet_in = {
+        93372036854775807ULL,963497880,963498088,"QRSTUVWXYZABCDEFGHI"
     };
-    mavlink_set_antenna_coordinates_arp_tc_t packet1, packet2;
+    mavlink_registry_int_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
-        packet1.latitude = packet_in.latitude;
-        packet1.longitude = packet_in.longitude;
+        packet1.timestamp = packet_in.timestamp;
+        packet1.key_id = packet_in.key_id;
+        packet1.value = packet_in.value;
         
+        mav_array_memcpy(packet1.key_name, packet_in.key_name, sizeof(char)*20);
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
         if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
            // cope with extensions
-           memset(MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN);
+           memset(MAVLINK_MSG_ID_REGISTRY_INT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_REGISTRY_INT_TM_MIN_LEN);
         }
 #endif
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_antenna_coordinates_arp_tc_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_set_antenna_coordinates_arp_tc_decode(&msg, &packet2);
+    mavlink_msg_registry_int_tm_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_registry_int_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_antenna_coordinates_arp_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
-    mavlink_msg_set_antenna_coordinates_arp_tc_decode(&msg, &packet2);
+    mavlink_msg_registry_int_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.value );
+    mavlink_msg_registry_int_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
-    mavlink_msg_set_antenna_coordinates_arp_tc_decode(&msg, &packet2);
+    mavlink_msg_registry_int_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.value );
+    mavlink_msg_registry_int_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
@@ -2734,59 +2815,62 @@ static void mavlink_test_set_antenna_coordinates_arp_tc(uint8_t system_id, uint8
         for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
             comm_send_ch(MAVLINK_COMM_0, buffer[i]);
         }
-    mavlink_msg_set_antenna_coordinates_arp_tc_decode(last_msg, &packet2);
+    mavlink_msg_registry_int_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_antenna_coordinates_arp_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
-    mavlink_msg_set_antenna_coordinates_arp_tc_decode(last_msg, &packet2);
+    mavlink_msg_registry_int_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.value );
+    mavlink_msg_registry_int_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("SET_ANTENNA_COORDINATES_ARP_TC") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC) != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("REGISTRY_INT_TM") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_REGISTRY_INT_TM) != NULL);
 #endif
 }
 
-static void mavlink_test_set_rocket_coordinates_arp_tc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+static void mavlink_test_registry_coord_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_SET_ROCKET_COORDINATES_ARP_TC >= 256) {
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_REGISTRY_COORD_TM >= 256) {
             return;
         }
 #endif
     mavlink_message_t msg;
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
-    mavlink_set_rocket_coordinates_arp_tc_t packet_in = {
-        17.0,45.0
+    mavlink_registry_coord_tm_t packet_in = {
+        93372036854775807ULL,963497880,101.0,129.0,"UVWXYZABCDEFGHIJKLM"
     };
-    mavlink_set_rocket_coordinates_arp_tc_t packet1, packet2;
+    mavlink_registry_coord_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
+        packet1.timestamp = packet_in.timestamp;
+        packet1.key_id = packet_in.key_id;
         packet1.latitude = packet_in.latitude;
         packet1.longitude = packet_in.longitude;
         
+        mav_array_memcpy(packet1.key_name, packet_in.key_name, sizeof(char)*20);
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
         if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
            // cope with extensions
-           memset(MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN);
+           memset(MAVLINK_MSG_ID_REGISTRY_COORD_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_REGISTRY_COORD_TM_MIN_LEN);
         }
 #endif
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_rocket_coordinates_arp_tc_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_set_rocket_coordinates_arp_tc_decode(&msg, &packet2);
+    mavlink_msg_registry_coord_tm_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_registry_coord_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_rocket_coordinates_arp_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
-    mavlink_msg_set_rocket_coordinates_arp_tc_decode(&msg, &packet2);
+    mavlink_msg_registry_coord_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.latitude , packet1.longitude );
+    mavlink_msg_registry_coord_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
-    mavlink_msg_set_rocket_coordinates_arp_tc_decode(&msg, &packet2);
+    mavlink_msg_registry_coord_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.latitude , packet1.longitude );
+    mavlink_msg_registry_coord_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
@@ -2794,64 +2878,90 @@ static void mavlink_test_set_rocket_coordinates_arp_tc(uint8_t system_id, uint8_
         for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
             comm_send_ch(MAVLINK_COMM_0, buffer[i]);
         }
-    mavlink_msg_set_rocket_coordinates_arp_tc_decode(last_msg, &packet2);
+    mavlink_msg_registry_coord_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_set_rocket_coordinates_arp_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
-    mavlink_msg_set_rocket_coordinates_arp_tc_decode(last_msg, &packet2);
+    mavlink_msg_registry_coord_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.key_id , packet1.key_name , packet1.latitude , packet1.longitude );
+    mavlink_msg_registry_coord_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("SET_ROCKET_COORDINATES_ARP_TC") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC) != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("REGISTRY_COORD_TM") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_REGISTRY_COORD_TM) != NULL);
 #endif
 }
 
-static void mavlink_test_sys_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+static void mavlink_test_arp_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_SYS_TM >= 256) {
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ARP_TM >= 256) {
             return;
         }
 #endif
     mavlink_message_t msg;
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
-    mavlink_sys_tm_t packet_in = {
-        93372036854775807ULL,29,96,163,230,41,108
+    mavlink_arp_tm_t packet_in = {
+        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,21187,21291,21395,21499,21603,21707,21811,21915,22019,22123,37,104,171,238,49
     };
-    mavlink_sys_tm_t packet1, packet2;
+    mavlink_arp_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.timestamp = packet_in.timestamp;
-        packet1.logger = packet_in.logger;
-        packet1.event_broker = packet_in.event_broker;
-        packet1.radio = packet_in.radio;
-        packet1.pin_observer = packet_in.pin_observer;
-        packet1.sensors = packet_in.sensors;
-        packet1.board_scheduler = packet_in.board_scheduler;
+        packet1.yaw = packet_in.yaw;
+        packet1.pitch = packet_in.pitch;
+        packet1.roll = packet_in.roll;
+        packet1.target_yaw = packet_in.target_yaw;
+        packet1.target_pitch = packet_in.target_pitch;
+        packet1.stepperX_pos = packet_in.stepperX_pos;
+        packet1.stepperX_delta = packet_in.stepperX_delta;
+        packet1.stepperX_speed = packet_in.stepperX_speed;
+        packet1.stepperY_pos = packet_in.stepperY_pos;
+        packet1.stepperY_delta = packet_in.stepperY_delta;
+        packet1.stepperY_speed = packet_in.stepperY_speed;
+        packet1.gps_latitude = packet_in.gps_latitude;
+        packet1.gps_longitude = packet_in.gps_longitude;
+        packet1.gps_height = packet_in.gps_height;
+        packet1.main_rx_rssi = packet_in.main_rx_rssi;
+        packet1.payload_rx_rssi = packet_in.payload_rx_rssi;
+        packet1.battery_voltage = packet_in.battery_voltage;
+        packet1.main_packet_tx_error_count = packet_in.main_packet_tx_error_count;
+        packet1.main_tx_bitrate = packet_in.main_tx_bitrate;
+        packet1.main_packet_rx_success_count = packet_in.main_packet_rx_success_count;
+        packet1.main_packet_rx_drop_count = packet_in.main_packet_rx_drop_count;
+        packet1.main_rx_bitrate = packet_in.main_rx_bitrate;
+        packet1.payload_packet_tx_error_count = packet_in.payload_packet_tx_error_count;
+        packet1.payload_tx_bitrate = packet_in.payload_tx_bitrate;
+        packet1.payload_packet_rx_success_count = packet_in.payload_packet_rx_success_count;
+        packet1.payload_packet_rx_drop_count = packet_in.payload_packet_rx_drop_count;
+        packet1.payload_rx_bitrate = packet_in.payload_rx_bitrate;
+        packet1.gps_fix = packet_in.gps_fix;
+        packet1.main_radio_present = packet_in.main_radio_present;
+        packet1.payload_radio_present = packet_in.payload_radio_present;
+        packet1.ethernet_present = packet_in.ethernet_present;
+        packet1.ethernet_status = packet_in.ethernet_status;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
         if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
            // cope with extensions
-           memset(MAVLINK_MSG_ID_SYS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYS_TM_MIN_LEN);
+           memset(MAVLINK_MSG_ID_ARP_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ARP_TM_MIN_LEN);
         }
 #endif
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_sys_tm_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_sys_tm_decode(&msg, &packet2);
+    mavlink_msg_arp_tm_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_arp_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_sys_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.pin_observer , packet1.sensors , packet1.board_scheduler );
-    mavlink_msg_sys_tm_decode(&msg, &packet2);
+    mavlink_msg_arp_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
+    mavlink_msg_arp_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_sys_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.pin_observer , packet1.sensors , packet1.board_scheduler );
-    mavlink_msg_sys_tm_decode(&msg, &packet2);
+    mavlink_msg_arp_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
+    mavlink_msg_arp_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
@@ -2859,64 +2969,66 @@ static void mavlink_test_sys_tm(uint8_t system_id, uint8_t component_id, mavlink
         for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
             comm_send_ch(MAVLINK_COMM_0, buffer[i]);
         }
-    mavlink_msg_sys_tm_decode(last_msg, &packet2);
+    mavlink_msg_arp_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_sys_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.pin_observer , packet1.sensors , packet1.board_scheduler );
-    mavlink_msg_sys_tm_decode(last_msg, &packet2);
+    mavlink_msg_arp_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
+    mavlink_msg_arp_tm_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("SYS_TM") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SYS_TM) != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("ARP_TM") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ARP_TM) != NULL);
 #endif
 }
 
-static void mavlink_test_fsm_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+static void mavlink_test_sys_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
     mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
-        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FSM_TM >= 256) {
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SYS_TM >= 256) {
             return;
         }
 #endif
     mavlink_message_t msg;
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
-    mavlink_fsm_tm_t packet_in = {
-        93372036854775807ULL,29,96,163,230,41,108
+    mavlink_sys_tm_t packet_in = {
+        93372036854775807ULL,29,96,163,230,41,108,175,242
     };
-    mavlink_fsm_tm_t packet1, packet2;
+    mavlink_sys_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.timestamp = packet_in.timestamp;
-        packet1.ada_state = packet_in.ada_state;
-        packet1.abk_state = packet_in.abk_state;
-        packet1.dpl_state = packet_in.dpl_state;
-        packet1.fmm_state = packet_in.fmm_state;
-        packet1.nas_state = packet_in.nas_state;
-        packet1.wes_state = packet_in.wes_state;
+        packet1.logger = packet_in.logger;
+        packet1.event_broker = packet_in.event_broker;
+        packet1.radio = packet_in.radio;
+        packet1.sensors = packet_in.sensors;
+        packet1.actuators = packet_in.actuators;
+        packet1.pin_handler = packet_in.pin_handler;
+        packet1.can_handler = packet_in.can_handler;
+        packet1.scheduler = packet_in.scheduler;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
         if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
            // cope with extensions
-           memset(MAVLINK_MSG_ID_FSM_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FSM_TM_MIN_LEN);
+           memset(MAVLINK_MSG_ID_SYS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYS_TM_MIN_LEN);
         }
 #endif
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_fsm_tm_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_fsm_tm_decode(&msg, &packet2);
+    mavlink_msg_sys_tm_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_sys_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_fsm_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state , packet1.wes_state );
-    mavlink_msg_fsm_tm_decode(&msg, &packet2);
+    mavlink_msg_sys_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.sensors , packet1.actuators , packet1.pin_handler , packet1.can_handler , packet1.scheduler );
+    mavlink_msg_sys_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_fsm_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state , packet1.wes_state );
-    mavlink_msg_fsm_tm_decode(&msg, &packet2);
+    mavlink_msg_sys_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.sensors , packet1.actuators , packet1.pin_handler , packet1.can_handler , packet1.scheduler );
+    mavlink_msg_sys_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
@@ -2924,17 +3036,17 @@ static void mavlink_test_fsm_tm(uint8_t system_id, uint8_t component_id, mavlink
         for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
             comm_send_ch(MAVLINK_COMM_0, buffer[i]);
         }
-    mavlink_msg_fsm_tm_decode(last_msg, &packet2);
+    mavlink_msg_sys_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_fsm_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state , packet1.wes_state );
-    mavlink_msg_fsm_tm_decode(last_msg, &packet2);
+    mavlink_msg_sys_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.sensors , packet1.actuators , packet1.pin_handler , packet1.can_handler , packet1.scheduler );
+    mavlink_msg_sys_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("FSM_TM") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_FSM_TM) != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("SYS_TM") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SYS_TM) != NULL);
 #endif
 }
 
@@ -3078,6 +3190,68 @@ static void mavlink_test_mavlink_stats_tm(uint8_t system_id, uint8_t component_i
 #endif
 }
 
+static void mavlink_test_can_stats_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_CAN_STATS_TM >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_can_stats_tm_t packet_in = {
+        93372036854775807ULL,73.0,101.0,129.0
+    };
+    mavlink_can_stats_tm_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.timestamp = packet_in.timestamp;
+        packet1.payload_bit_rate = packet_in.payload_bit_rate;
+        packet1.total_bit_rate = packet_in.total_bit_rate;
+        packet1.load_percent = packet_in.load_percent;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAN_STATS_TM_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_can_stats_tm_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_can_stats_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_can_stats_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.payload_bit_rate , packet1.total_bit_rate , packet1.load_percent );
+    mavlink_msg_can_stats_tm_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_can_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.payload_bit_rate , packet1.total_bit_rate , packet1.load_percent );
+    mavlink_msg_can_stats_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_can_stats_tm_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_can_stats_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.payload_bit_rate , packet1.total_bit_rate , packet1.load_percent );
+    mavlink_msg_can_stats_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("CAN_STATS_TM") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_CAN_STATS_TM) != NULL);
+#endif
+}
+
 static void mavlink_test_task_stats_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -3090,17 +3264,21 @@ static void mavlink_test_task_stats_tm(uint8_t system_id, uint8_t component_id,
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_task_stats_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,18483,211
+        93372036854775807ULL,963497880,963498088,129.0,157.0,185.0,213.0,241.0,269.0,19315,19419
     };
     mavlink_task_stats_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.timestamp = packet_in.timestamp;
-        packet1.task_min = packet_in.task_min;
-        packet1.task_max = packet_in.task_max;
-        packet1.task_mean = packet_in.task_mean;
-        packet1.task_stddev = packet_in.task_stddev;
-        packet1.task_period = packet_in.task_period;
+        packet1.task_missed_events = packet_in.task_missed_events;
+        packet1.task_failed_events = packet_in.task_failed_events;
+        packet1.task_activation_mean = packet_in.task_activation_mean;
+        packet1.task_activation_stddev = packet_in.task_activation_stddev;
+        packet1.task_period_mean = packet_in.task_period_mean;
+        packet1.task_period_stddev = packet_in.task_period_stddev;
+        packet1.task_workload_mean = packet_in.task_workload_mean;
+        packet1.task_workload_stddev = packet_in.task_workload_stddev;
         packet1.task_id = packet_in.task_id;
+        packet1.task_period = packet_in.task_period;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -3115,12 +3293,12 @@ static void mavlink_test_task_stats_tm(uint8_t system_id, uint8_t component_id,
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_task_stats_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_min , packet1.task_max , packet1.task_mean , packet1.task_stddev );
+    mavlink_msg_task_stats_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_missed_events , packet1.task_failed_events , packet1.task_activation_mean , packet1.task_activation_stddev , packet1.task_period_mean , packet1.task_period_stddev , packet1.task_workload_mean , packet1.task_workload_stddev );
     mavlink_msg_task_stats_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_min , packet1.task_max , packet1.task_mean , packet1.task_stddev );
+    mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_missed_events , packet1.task_failed_events , packet1.task_activation_mean , packet1.task_activation_stddev , packet1.task_period_mean , packet1.task_period_stddev , packet1.task_workload_mean , packet1.task_workload_stddev );
     mavlink_msg_task_stats_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3133,7 +3311,7 @@ static void mavlink_test_task_stats_tm(uint8_t system_id, uint8_t component_id,
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_task_stats_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_min , packet1.task_max , packet1.task_mean , packet1.task_stddev );
+    mavlink_msg_task_stats_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_missed_events , packet1.task_failed_events , packet1.task_activation_mean , packet1.task_activation_stddev , packet1.task_period_mean , packet1.task_period_stddev , packet1.task_workload_mean , packet1.task_workload_stddev );
     mavlink_msg_task_stats_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3368,7 +3546,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,1137.0,241,52,119,186,253,64,131,198,9,76,143,210
+        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
     };
     mavlink_rocket_flight_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -3407,10 +3585,8 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i
         packet1.nas_bias_x = packet_in.nas_bias_x;
         packet1.nas_bias_y = packet_in.nas_bias_y;
         packet1.nas_bias_z = packet_in.nas_bias_z;
-        packet1.pin_quick_connector = packet_in.pin_quick_connector;
         packet1.battery_voltage = packet_in.battery_voltage;
         packet1.cam_battery_voltage = packet_in.cam_battery_voltage;
-        packet1.current_consumption = packet_in.current_consumption;
         packet1.temperature = packet_in.temperature;
         packet1.ada_state = packet_in.ada_state;
         packet1.fmm_state = packet_in.fmm_state;
@@ -3423,7 +3599,6 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i
         packet1.pin_nosecone = packet_in.pin_nosecone;
         packet1.pin_expulsion = packet_in.pin_expulsion;
         packet1.cutter_presence = packet_in.cutter_presence;
-        packet1.logger_error = packet_in.logger_error;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -3438,12 +3613,12 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_rocket_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_quick_connector , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
+    mavlink_msg_rocket_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.temperature );
     mavlink_msg_rocket_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_quick_connector , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
+    mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.temperature );
     mavlink_msg_rocket_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3456,7 +3631,7 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_rocket_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_quick_connector , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
+    mavlink_msg_rocket_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.temperature );
     mavlink_msg_rocket_flight_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3478,7 +3653,7 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_payload_flight_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,217,28,95,162,229,40,107
+        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,95
     };
     mavlink_payload_flight_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -3518,15 +3693,14 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_
         packet1.wes_e = packet_in.wes_e;
         packet1.battery_voltage = packet_in.battery_voltage;
         packet1.cam_battery_voltage = packet_in.cam_battery_voltage;
-        packet1.current_consumption = packet_in.current_consumption;
         packet1.temperature = packet_in.temperature;
         packet1.fmm_state = packet_in.fmm_state;
         packet1.nas_state = packet_in.nas_state;
         packet1.wes_state = packet_in.wes_state;
         packet1.gps_fix = packet_in.gps_fix;
+        packet1.pin_launch = packet_in.pin_launch;
         packet1.pin_nosecone = packet_in.pin_nosecone;
         packet1.cutter_presence = packet_in.cutter_presence;
-        packet1.logger_error = packet_in.logger_error;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -3541,12 +3715,12 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_payload_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.cutter_presence , 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_launch , packet1.pin_nosecone , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.temperature );
     mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.cutter_presence , 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_launch , packet1.pin_nosecone , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.temperature );
     mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3559,7 +3733,7 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_payload_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.cutter_presence , 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_launch , packet1.pin_nosecone , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.temperature );
     mavlink_msg_payload_flight_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3581,7 +3755,7 @@ static void mavlink_test_rocket_stats_tm(uint8_t system_id, uint8_t component_id
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_rocket_stats_tm_t packet_in = {
-        93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,93372036854777823ULL,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,963502040
+        93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,93372036854777823ULL,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,963502040,963502248,22227,171,238,49,116,183,250
     };
     mavlink_rocket_stats_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -3600,9 +3774,17 @@ static void mavlink_test_rocket_stats_tm(uint8_t system_id, uint8_t component_id
         packet1.apogee_alt = packet_in.apogee_alt;
         packet1.min_pressure = packet_in.min_pressure;
         packet1.ada_min_pressure = packet_in.ada_min_pressure;
-        packet1.dpl_vane_max_pressure = packet_in.dpl_vane_max_pressure;
+        packet1.dpl_bay_max_pressure = packet_in.dpl_bay_max_pressure;
         packet1.cpu_load = packet_in.cpu_load;
         packet1.free_heap = packet_in.free_heap;
+        packet1.log_good = packet_in.log_good;
+        packet1.log_number = packet_in.log_number;
+        packet1.payload_board_state = packet_in.payload_board_state;
+        packet1.motor_board_state = packet_in.motor_board_state;
+        packet1.payload_can_status = packet_in.payload_can_status;
+        packet1.motor_can_status = packet_in.motor_can_status;
+        packet1.rig_can_status = packet_in.rig_can_status;
+        packet1.hil_state = packet_in.hil_state;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -3617,12 +3799,12 @@ static void mavlink_test_rocket_stats_tm(uint8_t system_id, uint8_t component_id
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_rocket_stats_tm_pack(system_id, component_id, &msg , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_vane_max_pressure , packet1.cpu_load , packet1.free_heap );
+    mavlink_msg_rocket_stats_tm_pack(system_id, component_id, &msg , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_bay_max_pressure , packet1.cpu_load , packet1.free_heap , packet1.log_number , packet1.log_good , packet1.payload_board_state , packet1.motor_board_state , packet1.payload_can_status , packet1.motor_can_status , packet1.rig_can_status , packet1.hil_state );
     mavlink_msg_rocket_stats_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_rocket_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_vane_max_pressure , packet1.cpu_load , packet1.free_heap );
+    mavlink_msg_rocket_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_bay_max_pressure , packet1.cpu_load , packet1.free_heap , packet1.log_number , packet1.log_good , packet1.payload_board_state , packet1.motor_board_state , packet1.payload_can_status , packet1.motor_can_status , packet1.rig_can_status , packet1.hil_state );
     mavlink_msg_rocket_stats_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3635,7 +3817,7 @@ static void mavlink_test_rocket_stats_tm(uint8_t system_id, uint8_t component_id
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_rocket_stats_tm_send(MAVLINK_COMM_1 , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_vane_max_pressure , packet1.cpu_load , packet1.free_heap );
+    mavlink_msg_rocket_stats_tm_send(MAVLINK_COMM_1 , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_bay_max_pressure , packet1.cpu_load , packet1.free_heap , packet1.log_number , packet1.log_good , packet1.payload_board_state , packet1.motor_board_state , packet1.payload_can_status , packet1.motor_can_status , packet1.rig_can_status , packet1.hil_state );
     mavlink_msg_rocket_stats_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3657,7 +3839,7 @@ static void mavlink_test_payload_stats_tm(uint8_t system_id, uint8_t component_i
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_payload_stats_tm_t packet_in = {
-        93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,963501208
+        93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,963501208,963501416,21395,123,190,1,68,135,202
     };
     mavlink_payload_stats_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -3676,6 +3858,14 @@ static void mavlink_test_payload_stats_tm(uint8_t system_id, uint8_t component_i
         packet1.min_pressure = packet_in.min_pressure;
         packet1.cpu_load = packet_in.cpu_load;
         packet1.free_heap = packet_in.free_heap;
+        packet1.log_good = packet_in.log_good;
+        packet1.log_number = packet_in.log_number;
+        packet1.main_board_state = packet_in.main_board_state;
+        packet1.motor_board_state = packet_in.motor_board_state;
+        packet1.main_can_status = packet_in.main_can_status;
+        packet1.motor_can_status = packet_in.motor_can_status;
+        packet1.rig_can_status = packet_in.rig_can_status;
+        packet1.hil_state = packet_in.hil_state;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -3690,12 +3880,12 @@ static void mavlink_test_payload_stats_tm(uint8_t system_id, uint8_t component_i
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_payload_stats_tm_pack(system_id, component_id, &msg , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap );
+    mavlink_msg_payload_stats_tm_pack(system_id, component_id, &msg , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap , packet1.log_number , packet1.log_good , packet1.main_board_state , packet1.motor_board_state , packet1.main_can_status , packet1.motor_can_status , packet1.rig_can_status , packet1.hil_state );
     mavlink_msg_payload_stats_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_payload_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap );
+    mavlink_msg_payload_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap , packet1.log_number , packet1.log_good , packet1.main_board_state , packet1.motor_board_state , packet1.main_can_status , packet1.motor_can_status , packet1.rig_can_status , packet1.hil_state );
     mavlink_msg_payload_stats_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3708,7 +3898,7 @@ static void mavlink_test_payload_stats_tm(uint8_t system_id, uint8_t component_i
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_payload_stats_tm_send(MAVLINK_COMM_1 , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap );
+    mavlink_msg_payload_stats_tm_send(MAVLINK_COMM_1 , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap , packet1.log_number , packet1.log_good , packet1.main_board_state , packet1.motor_board_state , packet1.main_can_status , packet1.motor_can_status , packet1.rig_can_status , packet1.hil_state );
     mavlink_msg_payload_stats_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3730,7 +3920,7 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_gse_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,101,168,235,46,113,180,247,58,125,192,3
+        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,963499336,19315,3,70,137,204,15,82,149,216,27,94,161,228,39,106
     };
     mavlink_gse_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -3741,7 +3931,9 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink
         packet1.vessel_pressure = packet_in.vessel_pressure;
         packet1.battery_voltage = packet_in.battery_voltage;
         packet1.current_consumption = packet_in.current_consumption;
-        packet1.arming_state = packet_in.arming_state;
+        packet1.umbilical_current_consumption = packet_in.umbilical_current_consumption;
+        packet1.log_good = packet_in.log_good;
+        packet1.log_number = packet_in.log_number;
         packet1.filling_valve_state = packet_in.filling_valve_state;
         packet1.venting_valve_state = packet_in.venting_valve_state;
         packet1.release_valve_state = packet_in.release_valve_state;
@@ -3749,9 +3941,13 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink
         packet1.nitrogen_valve_state = packet_in.nitrogen_valve_state;
         packet1.gmm_state = packet_in.gmm_state;
         packet1.tars_state = packet_in.tars_state;
-        packet1.main_board_status = packet_in.main_board_status;
-        packet1.payload_board_status = packet_in.payload_board_status;
-        packet1.motor_board_status = packet_in.motor_board_status;
+        packet1.arming_state = packet_in.arming_state;
+        packet1.main_board_state = packet_in.main_board_state;
+        packet1.payload_board_state = packet_in.payload_board_state;
+        packet1.motor_board_state = packet_in.motor_board_state;
+        packet1.main_can_status = packet_in.main_can_status;
+        packet1.payload_can_status = packet_in.payload_can_status;
+        packet1.motor_can_status = packet_in.motor_can_status;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -3766,12 +3962,12 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_gse_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.nitrogen_valve_state , packet1.gmm_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
+    mavlink_msg_gse_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.nitrogen_valve_state , packet1.gmm_state , packet1.tars_state , packet1.arming_state , packet1.battery_voltage , packet1.current_consumption , packet1.umbilical_current_consumption , packet1.main_board_state , packet1.payload_board_state , packet1.motor_board_state , packet1.main_can_status , packet1.payload_can_status , packet1.motor_can_status , packet1.log_number , packet1.log_good );
     mavlink_msg_gse_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_gse_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.nitrogen_valve_state , packet1.gmm_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
+    mavlink_msg_gse_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.nitrogen_valve_state , packet1.gmm_state , packet1.tars_state , packet1.arming_state , packet1.battery_voltage , packet1.current_consumption , packet1.umbilical_current_consumption , packet1.main_board_state , packet1.payload_board_state , packet1.motor_board_state , packet1.main_can_status , packet1.payload_can_status , packet1.motor_can_status , packet1.log_number , packet1.log_good );
     mavlink_msg_gse_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3784,7 +3980,7 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_gse_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.nitrogen_valve_state , packet1.gmm_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
+    mavlink_msg_gse_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.nitrogen_valve_state , packet1.gmm_state , packet1.tars_state , packet1.arming_state , packet1.battery_voltage , packet1.current_consumption , packet1.umbilical_current_consumption , packet1.main_board_state , packet1.payload_board_state , packet1.motor_board_state , packet1.main_can_status , packet1.payload_can_status , packet1.motor_can_status , packet1.log_number , packet1.log_good );
     mavlink_msg_gse_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3806,7 +4002,7 @@ static void mavlink_test_motor_tm(uint8_t system_id, uint8_t component_id, mavli
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_motor_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,101,168
+        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,963498920,18899,235,46,113
     };
     mavlink_motor_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -3816,9 +4012,11 @@ static void mavlink_test_motor_tm(uint8_t system_id, uint8_t component_id, mavli
         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.log_good = packet_in.log_good;
+        packet1.log_number = packet_in.log_number;
         packet1.main_valve_state = packet_in.main_valve_state;
         packet1.venting_valve_state = packet_in.venting_valve_state;
+        packet1.hil_state = packet_in.hil_state;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -3833,12 +4031,12 @@ static void mavlink_test_motor_tm(uint8_t system_id, uint8_t component_id, mavli
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_motor_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.current_consumption );
+    mavlink_msg_motor_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.log_number , packet1.log_good , packet1.hil_state );
     mavlink_msg_motor_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_motor_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.current_consumption );
+    mavlink_msg_motor_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.log_number , packet1.log_good , packet1.hil_state );
     mavlink_msg_motor_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3851,7 +4049,7 @@ static void mavlink_test_motor_tm(uint8_t system_id, uint8_t component_id, mavli
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_motor_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.current_consumption );
+    mavlink_msg_motor_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.log_number , packet1.log_good , packet1.hil_state );
     mavlink_msg_motor_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3869,11 +4067,12 @@ static void mavlink_test_lyra(uint8_t system_id, uint8_t component_id, mavlink_m
     mavlink_test_sensor_tm_request_tc(system_id, component_id, last_msg);
     mavlink_test_servo_tm_request_tc(system_id, component_id, last_msg);
     mavlink_test_set_servo_angle_tc(system_id, component_id, last_msg);
-    mavlink_test_wiggle_servo_tc(system_id, component_id, last_msg);
     mavlink_test_reset_servo_tc(system_id, component_id, last_msg);
+    mavlink_test_wiggle_servo_tc(system_id, component_id, last_msg);
     mavlink_test_set_reference_altitude_tc(system_id, component_id, last_msg);
     mavlink_test_set_reference_temperature_tc(system_id, component_id, last_msg);
     mavlink_test_set_orientation_tc(system_id, component_id, last_msg);
+    mavlink_test_set_orientation_quat_tc(system_id, component_id, last_msg);
     mavlink_test_set_coordinates_tc(system_id, component_id, last_msg);
     mavlink_test_raw_event_tc(system_id, component_id, last_msg);
     mavlink_test_set_deployment_altitude_tc(system_id, component_id, last_msg);
@@ -3883,12 +4082,17 @@ static void mavlink_test_lyra(uint8_t system_id, uint8_t component_id, mavlink_m
     mavlink_test_set_valve_maximum_aperture_tc(system_id, component_id, last_msg);
     mavlink_test_conrig_state_tc(system_id, component_id, last_msg);
     mavlink_test_set_ignition_time_tc(system_id, component_id, last_msg);
-    mavlink_test_set_stepper_angle_tc(system_id, component_id, last_msg);
-    mavlink_test_set_stepper_steps_tc(system_id, component_id, last_msg);
     mavlink_test_set_nitrogen_time_tc(system_id, component_id, last_msg);
     mavlink_test_set_cooling_time_tc(system_id, component_id, last_msg);
+    mavlink_test_set_stepper_angle_tc(system_id, component_id, last_msg);
+    mavlink_test_set_stepper_steps_tc(system_id, component_id, last_msg);
+    mavlink_test_set_stepper_multiplier_tc(system_id, component_id, last_msg);
+    mavlink_test_set_antenna_coordinates_arp_tc(system_id, component_id, last_msg);
+    mavlink_test_set_rocket_coordinates_arp_tc(system_id, component_id, last_msg);
+    mavlink_test_arp_command_tc(system_id, component_id, last_msg);
     mavlink_test_ack_tm(system_id, component_id, last_msg);
     mavlink_test_nack_tm(system_id, component_id, last_msg);
+    mavlink_test_wack_tm(system_id, component_id, last_msg);
     mavlink_test_gps_tm(system_id, component_id, last_msg);
     mavlink_test_imu_tm(system_id, component_id, last_msg);
     mavlink_test_pressure_tm(system_id, component_id, last_msg);
@@ -3904,14 +4108,11 @@ static void mavlink_test_lyra(uint8_t system_id, uint8_t component_id, mavlink_m
     mavlink_test_registry_float_tm(system_id, component_id, last_msg);
     mavlink_test_registry_int_tm(system_id, component_id, last_msg);
     mavlink_test_registry_coord_tm(system_id, component_id, last_msg);
-    mavlink_test_receiver_tm(system_id, component_id, last_msg);
     mavlink_test_arp_tm(system_id, component_id, last_msg);
-    mavlink_test_set_antenna_coordinates_arp_tc(system_id, component_id, last_msg);
-    mavlink_test_set_rocket_coordinates_arp_tc(system_id, component_id, last_msg);
     mavlink_test_sys_tm(system_id, component_id, last_msg);
-    mavlink_test_fsm_tm(system_id, component_id, last_msg);
     mavlink_test_logger_tm(system_id, component_id, last_msg);
     mavlink_test_mavlink_stats_tm(system_id, component_id, last_msg);
+    mavlink_test_can_stats_tm(system_id, component_id, last_msg);
     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);
diff --git a/mavlink_lib/lyra/version.h b/mavlink_lib/lyra/version.h
index 7533ece1f3187c1f798f119bc474444f8c20707f..d4beaede7c6ea046a4c9f09b5fee9c9169d1b8da 100644
--- a/mavlink_lib/lyra/version.h
+++ b/mavlink_lib/lyra/version.h
@@ -7,8 +7,8 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Thu May 09 2024"
+#define MAVLINK_BUILD_DATE "Thu Jul 11 2024"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 176
+#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 167
  
 #endif // MAVLINK_VERSION_H
diff --git a/message_definitions/lyra.xml b/message_definitions/lyra.xml
index 6387e3c9e87f6524e31ac8fdc3e4047adacbf531..c13321d797aa462438d9a864d4bb271bd511f692 100644
--- a/message_definitions/lyra.xml
+++ b/message_definitions/lyra.xml
@@ -14,138 +14,149 @@
             <entry name="MAV_SYS_ID" value="1">
                 <description>State of init results about system hardware/software components</description>
             </entry>
-            <entry name="MAV_FSM_ID" value="2">
-                <description>States of all On-Board FSMs</description>
-            </entry>
-            <entry name="MAV_PIN_OBS_ID" value="3">
+            <entry name="MAV_PIN_OBS_ID" value="2">
                 <description>Pin observer data</description>
             </entry>
-            <entry name="MAV_LOGGER_ID" value="4">
+            <entry name="MAV_LOGGER_ID" value="3">
                 <description>SD Logger stats</description>
             </entry>
-            <entry name="MAV_MAVLINK_STATS" value="5">
+            <entry name="MAV_MAVLINK_STATS_ID" value="4">
                 <description>Mavlink driver stats</description>
             </entry>
-            <entry name="MAV_TASK_STATS_ID" value="6">
+            <entry name="MAV_TASK_STATS_ID" value="5">
                 <description>Task scheduler statistics answer: n mavlink messages where n is the number of tasks</description>
             </entry>
-            <entry name="MAV_ADA_ID" value="7">
+            <entry name="MAV_ADA_ID" value="6">
                 <description>ADA Status</description>
             </entry>
-            <entry name="MAV_NAS_ID" value="8">
+            <entry name="MAV_NAS_ID" value="7">
                 <description>NavigationSystem data</description>
             </entry>
-            <entry name="MAV_MEA_ID" value="9">
+            <entry name="MAV_MEA_ID" value="8">
                 <description>MEA Status</description>
             </entry>
-            <entry name="MAV_CAN_ID" value="10">
+            <entry name="MAV_CAN_STATS_ID" value="9">
                 <description>Canbus stats</description>
             </entry>
-            <entry name="MAV_FLIGHT_ID" value="11">
+            <entry name="MAV_FLIGHT_ID" value="10">
                 <description>Flight telemetry</description>
             </entry>
-            <entry name="MAV_STATS_ID" value="12">
+            <entry name="MAV_STATS_ID" value="11">
                 <description>Satistics telemetry</description>
             </entry>
-            <entry name="MAV_SENSORS_STATE_ID" value="13">
+            <entry name="MAV_SENSORS_STATE_ID" value="12">
                 <description>Sensors init state telemetry</description>
             </entry>
-            <entry name="MAV_GSE_ID" value="14">
+            <entry name="MAV_GSE_ID" value="13">
                 <description>Ground Segnement Equipment</description>
             </entry>
-            <entry name="MAV_MOTOR_ID" value="15">
+            <entry name="MAV_MOTOR_ID" value="14">
                 <description>Rocket Motor data</description>
             </entry>
-            <entry name="MAV_REGISTRY_ID" value="16">
+            <entry name="MAV_REGISTRY_ID" value="15">
                 <description>Command to fetch all registry keys</description>
             </entry>
         </enum>
         <enum name="SensorsTMList">
             <description>Enum list of all sensors telemetries that can be requested</description>
-            <entry name="MAV_GPS_ID" value="1">
-                <description>GPS data</description>
-            </entry>
-            <entry name="MAV_BMX160_ID" value="2">
+            <!-- PHYSICAL SENSORS NAMES -->
+            <entry name="MAV_BMX160_ID" value="1">
                 <description>BMX160 IMU data</description>
             </entry>
-            <entry name="MAV_VN100_ID" value="3">
+            <entry name="MAV_VN100_ID" value="2">
                 <description>VN100 IMU data</description>
             </entry>
-            <entry name="MAV_MPU9250_ID" value="4">
+            <entry name="MAV_MPU9250_ID" value="3">
                 <description>MPU9250 IMU data</description>
             </entry>
-            <entry name="MAV_ADS_ID" value="5">
+            <entry name="MAV_ADS131M08_ID" value="4">
                 <description>ADS 8 channel ADC data</description>
             </entry>
-            <entry name="MAV_MS5803_ID" value="6">
+            <entry name="MAV_MS5803_ID" value="5">
                 <description>MS5803 barometer data</description>
             </entry>
-            <entry name="MAV_BME280_ID" value="7">
+            <entry name="MAV_BME280_ID" value="6">
                 <description>BME280 barometer data</description>
             </entry>
-            <entry name="MAV_CURRENT_SENSE_ID" value="8">
+            <entry name="MAV_LIS3MDL_ID" value="7">
+                <description>LIS3MDL compass data</description>
+            </entry>
+            <entry name="MAV_LIS2MDL_ID" value="8">
+                <description>Magnetometer data</description>
+            </entry>
+            <entry name="MAV_LPS28DFW_ID" value="9">
+                <description>Pressure sensor data</description>
+            </entry>
+            <entry name="MAV_LSM6DSRX_ID" value="10">
+                <description>IMU data</description> 
+            </entry>
+            <entry name="MAV_H3LIS331DL_ID" value="11">
+                <description>400G accelerometer</description>
+            </entry>
+            <entry name="MAV_LPS22DF_ID" value="12">
+                <description>Pressure sensor data</description>
+            </entry>
+            <!-- GENERIC SENSORS NAMES -->
+            <!-- ROCKET -->
+            <entry name="MAV_GPS_ID" value="13">
+                <description>GPS data</description>
+            </entry>
+            <entry name="MAV_CURRENT_SENSE_ID" value="14">
                 <description>Electrical current sensors data</description>
             </entry>
-            <entry name="MAV_LIS3MDL_ID" value="9">
-                <description>LIS3MDL compass data</description>
+            <entry name="MAV_BATTERY_VOLTAGE_ID" value="15">
+                <description>Battery voltage data</description>
             </entry>
-            <entry name="MAV_DPL_PRESS_ID" value="10">
+            <entry name="MAV_ROTATED_IMU_ID" value="16">
+                <description>Load cell data</description>
+            </entry>
+            <entry name="MAV_DPL_PRESS_ID" value="17">
                 <description>Deployment pressure data</description>
             </entry>
-            <entry name="MAV_STATIC_PRESS_ID" value="11">
+            <entry name="MAV_STATIC_PRESS_ID" value="18">
                 <description>Static pressure data</description>
             </entry>
-            <entry name="MAV_PITOT_PRESS_ID" value="12">
+            <entry name="MAV_BACKUP_STATIC_PRESS_ID" value="19">
+                <description>Static pressure data</description>
+            </entry>
+            <entry name="MAV_STATIC_PITOT_PRESS_ID" value="20">
                 <description>Pitot pressure data</description>
             </entry>
-            <entry name="MAV_BATTERY_VOLTAGE_ID" value="13">
-                <description>Battery voltage data</description>
+            <entry name="MAV_TOTAL_PITOT_PRESS_ID" value="21">
+                <description>Pitot pressure data</description>
+            </entry>
+            <entry name="MAV_DYNAMIC_PITOT_PRESS_ID" value="22">
+                <description>Pitot pressure data</description>
             </entry>
-            <entry name="MAV_LOAD_CELL_ID" value="14">
+            <entry name="MAV_LOAD_CELL_ID" value="23">
                 <description>Load cell data</description>
             </entry>
             <!-- MOTOR -->
-            <entry name="MAV_FILLING_PRESS_ID" value="15">
-                <description>Filling line pressure</description>
-            </entry>
-            <entry name="MAV_TANK_TOP_PRESS_ID" value="16">
+            <entry name="MAV_TANK_TOP_PRESS_ID" value="24">
                 <description>Top tank pressure</description>
             </entry>
-            <entry name="MAV_TANK_BOTTOM_PRESS_ID" value="17">
+            <entry name="MAV_TANK_BOTTOM_PRESS_ID" value="25">
                 <description>Bottom tank pressure</description>
             </entry>
-            <entry name="MAV_TANK_TEMP_ID" value="18">
+            <entry name="MAV_TANK_TEMP_ID" value="26">
                 <description>Tank temperature</description>
             </entry>
-            <entry name="MAV_COMBUSTION_PRESS_ID" value="19">
+            <entry name="MAV_COMBUSTION_PRESS_ID" value="27">
                 <description>Combustion chamber pressure</description>
             </entry>
-            <entry name="MAV_VESSEL_PRESS_ID" value="20">
+            <!-- GSE -->
+            <entry name="MAV_FILLING_PRESS_ID" value="28">
+                <description>Filling line pressure</description>
+            </entry>
+            <entry name="MAV_VESSEL_PRESS_ID" value="29">
                 <description>Vessel pressure</description>
             </entry>
-            <!-- REFUELING -->
-            <entry name="MAV_LOAD_CELL_VESSEL_ID" value="21">
+            <entry name="MAV_LOAD_CELL_VESSEL_ID" value="30">
                 <description>Vessel tank weight</description>
             </entry>
-            <entry name="MAV_LOAD_CELL_TANK_ID" value="22">
+            <entry name="MAV_LOAD_CELL_TANK_ID" value="31">
                 <description>Tank weight</description>
             </entry>
-            <!-- GEMINI ROCKET -->
-            <entry name="MAV_LIS2MDL_ID" value="23">
-                <description>Magnetometer data</description>
-            </entry>
-            <entry name="MAV_LPS28DFW_ID" value="24">
-                <description>Pressure sensor data</description>
-            </entry>
-            <entry name="MAV_LSM6DSRX_ID" value="25">
-                <description>IMU data</description> 
-            </entry>
-            <entry name="MAV_H3LIS331DL_ID" value="26">
-                <description>400G accelerometer</description>
-            </entry>
-            <entry name="MAV_LPS22DF_ID" value="27">
-                <description>Pressure sensor data</description>
-            </entry>
         </enum>
         <enum name="MavCommandList">
             <description>Enum of the commands</description>
@@ -167,18 +178,18 @@
             <entry name="MAV_CMD_FORCE_LAUNCH" value="6">
                 <description>Command to force the launch state on the rocket</description>
             </entry>
-            <entry name="MAV_CMD_FORCE_LANDING" value="7">
-                <description>Command to communicate the end of the mission and close the file descriptors in the SD card</description>
-            </entry>
-            <entry name="MAV_CMD_FORCE_APOGEE" value="8">
-                <description>Command to trigger the apogee event</description>
+            <entry name="MAV_CMD_FORCE_ENGINE_SHUTDOWN" value="7">
+                <description>Command to trigger engine shutdown</description>
             </entry>
-            <entry name="MAV_CMD_FORCE_EXPULSION" value="9">
-                <description>Command to open the nosecone</description>
+            <entry name="MAV_CMD_FORCE_EXPULSION" value="8">
+                <description>Command to trigger nosecone expulsion</description>
             </entry>
-            <entry name="MAV_CMD_FORCE_DEPLOYMENT" value="10">
+            <entry name="MAV_CMD_FORCE_DEPLOYMENT" value="9">
                 <description>Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially</description>
             </entry>
+            <entry name="MAV_CMD_FORCE_LANDING" value="10">
+                <description>Command to communicate the end of the mission and close the file descriptors in the SD card</description>
+            </entry>
             <entry name="MAV_CMD_START_LOGGING" value="11">
                 <description>Command to enable sensor logging</description>
             </entry>
@@ -212,9 +223,12 @@
             <entry name="MAV_CMD_REGISTRY_CLEAR" value="21">
                 <description>Command to clear the registry</description>
             </entry>
+            <entry name="MAV_CMD_ENTER_HIL" value="22">
+                <description>Command to enter HIL mode at next reboot</description>
+            </entry>
         </enum>
         <enum name="ServosList">
-            <description>Enum of all the servos used on Gemini</description>
+            <description>Enum of all the servos</description>
             <entry name="AIR_BRAKES_SERVO" value="1"></entry>
             <entry name="EXPULSION_SERVO" value="2"></entry>
             <entry name="PARAFOIL_LEFT_SERVO" value="3"></entry>
@@ -226,16 +240,14 @@
             <entry name="DISCONNECT_SERVO" value="9"></entry> <!-- AUTOMATIC DETACH OF REFUELING QUICK CONNECTOR-->
         </enum>
         <enum name="StepperList">
-            <description>Enum of all the steppers used on Gemini systems</description>
+            <description>Enum of all the steppers</description>
             <entry name="STEPPER_X" value="1"></entry>
             <entry name="STEPPER_Y" value="2"></entry>
         </enum>
         <enum name="PinsList">
-            <description>Enum of all the pins used on Gemini</description>
-            <entry name="LAUNCH_PIN" value="1"></entry>
+            <description>Enum of all the pins</description>
+            <entry name="RAMP_PIN" value="1"></entry>
             <entry name="NOSECONE_PIN" value="2"></entry>
-            <entry name="DEPLOYMENT_PIN" value="3"></entry>
-            <entry name="QUICK_CONNECTOR_PIN" value="4"></entry>
         </enum>
     </enums>
     <messages>
@@ -265,12 +277,12 @@
             <field name="servo_id" type="uint8_t">A member of the ServosList enum</field>
             <field name="angle" type="float">Servo angle in normalized value [0-1]</field>
         </message>
-        <message id="7" name="WIGGLE_SERVO_TC">
-            <description>Wiggles the specified servo</description>
+        <message id="7" name="RESET_SERVO_TC">
+            <description>Resets the specified servo</description>
             <field name="servo_id" type="uint8_t">A member of the ServosList enum</field>
         </message>
-        <message id="8" name="RESET_SERVO_TC">
-            <description>Resets the specified servo</description>
+        <message id="8" name="WIGGLE_SERVO_TC">
+            <description>Wiggles the specified servo</description>
             <field name="servo_id" type="uint8_t">A member of the ServosList enum</field>
         </message>
         <message id="9" name="SET_REFERENCE_ALTITUDE_TC">
@@ -287,42 +299,49 @@
             <field name="pitch" type="float" units="deg">Pitch angle</field>
             <field name="roll" type="float" units="deg">Roll angle</field>
         </message>
-        <message id="12" name="SET_COORDINATES_TC">
+        <message id="12" name="SET_ORIENTATION_QUAT_TC">
+            <description>Sets current orientation for the navigation system using a quaternion</description>
+            <field name="quat_x" type="float">Quaternion x component</field>
+            <field name="quat_y" type="float">Quaternion y component</field>
+            <field name="quat_z" type="float">Quaternion z component</field>
+            <field name="quat_w" type="float">Quaternion w component</field>
+        </message>
+        <message id="13" name="SET_COORDINATES_TC">
             <description>Sets current coordinates</description>
             <field name="latitude" type="float" units="deg">Latitude</field>
             <field name="longitude" type="float" units="deg">Longitude</field>
         </message>
-        <message id="13" name="RAW_EVENT_TC">
+        <message id="14" name="RAW_EVENT_TC">
             <description>TC containing a raw event to be posted directly in the EventBroker</description>
             <field name="topic_id" type="uint8_t">Id of the topic to which the event should be posted</field>
             <field name="event_id" type="uint8_t">Id of the event to be posted</field>
         </message>
-        <message id="14" name="SET_DEPLOYMENT_ALTITUDE_TC">
+        <message id="15" name="SET_DEPLOYMENT_ALTITUDE_TC">
             <description>Sets the deployment altitude for the main parachute</description>
             <field name="dpl_altitude" type="float" units="m">Deployment altitude</field>
         </message>
-        <message id="15" name="SET_TARGET_COORDINATES_TC">
+        <message id="16" name="SET_TARGET_COORDINATES_TC">
             <description>Sets the target coordinates</description>
             <field name="latitude" type="float" units="deg">Latitude</field>
             <field name="longitude" type="float" units="deg">Longitude</field>
         </message>
-        <message id="16" name="SET_ALGORITHM_TC">
-            <description>Sets the algorithm number (for parafoil guidance and GSE tars)</description>
+        <message id="17" name="SET_ALGORITHM_TC">
+            <description>Sets the algorithm number (for parafoil guidance)</description>
             <field name="algorithm_number" type="uint8_t">Algorithm number</field>
         </message>
 
-        <!-- GSE -->
-        <message id="17" name="SET_ATOMIC_VALVE_TIMING_TC">
+        <!-- FROM GROUND TO GSE -->
+        <message id="30" name="SET_ATOMIC_VALVE_TIMING_TC">
             <description>Sets the maximum time that the valves can be open atomically</description>
             <field name="servo_id" type="uint8_t">A member of the ServosList enum</field>
             <field name="maximum_timing" type="uint32_t" units="ms">Maximum timing in [ms]</field>
         </message>
-        <message id="18" name="SET_VALVE_MAXIMUM_APERTURE_TC">
+        <message id="31" name="SET_VALVE_MAXIMUM_APERTURE_TC">
             <description>Sets the maximum aperture of the specified valve. Set as value from 0 to 1</description>
             <field name="servo_id" type="uint8_t">A member of the ServosList enum</field>
             <field name="maximum_aperture" type="float">Maximum aperture</field>
         </message>
-        <message id="19" name="CONRIG_STATE_TC">
+        <message id="32" name="CONRIG_STATE_TC">
             <description>Send the state of the conrig buttons</description>
             <field name="ignition_btn" type="uint8_t">Ignition button pressed</field>
             <field name="filling_valve_btn" type="uint8_t">Open filling valve pressed</field>
@@ -332,32 +351,55 @@
             <field name="start_tars_btn" type="uint8_t">Startup TARS pressed</field>
             <field name="arm_switch" type="uint8_t">Arming switch state</field>
         </message>
-        <message id="20" name="SET_IGNITION_TIME_TC">
+        <message id="33" name="SET_IGNITION_TIME_TC">
             <description>Sets the time in ms that the igniter stays on before the oxidant valve is opened</description>
             <field name="timing" type="uint32_t" units="ms">Timing in [ms]</field>
         </message>
-        <message id="21" name="SET_STEPPER_ANGLE_TC">
+        <message id="34" name="SET_NITROGEN_TIME_TC">
+            <description>Sets the time in ms that the nitrogen will stay open</description>
+            <field name="timing" type="uint32_t" units="ms">Timing in [ms]</field>
+        </message>
+        <message id="35" name="SET_COOLING_TIME_TC">
+            <description>Sets the time in ms that the system will wait before disarming after firing</description>
+            <field name="timing" type="uint32_t" units="ms">Timing in [ms]</field>
+        </message>
+
+        <!-- FROM GROUND TO ARP -->
+        <message id="60" name="SET_STEPPER_ANGLE_TC">
             <description>Move the stepper of a certain angle</description>
             <field name="stepper_id" type="uint8_t">A member of the StepperList enum</field>
             <field name="angle" type="float">Stepper angle in degrees</field>
         </message>
-        <message id="22" name="SET_STEPPER_STEPS_TC">
+        <message id="61" name="SET_STEPPER_STEPS_TC">
             <description>Move the stepper of a certain amount of steps</description>
             <field name="stepper_id" type="uint8_t">A member of the StepperList enum</field>
             <field name="steps" type="float">Number of steps</field>
         </message>
-        <message id="23" name="SET_NITROGEN_TIME_TC">
-            <description>Sets the time in ms that the nitrogen will stay open</description>
-            <field name="timing" type="uint32_t" units="ms">Timing in [ms]</field>
+        <message id="62" name="SET_STEPPER_MULTIPLIER_TC">
+            <description>Set the multiplier of the stepper</description>
+            <field name="stepper_id" type="uint8_t">A member of the StepperList enum</field>
+            <field name="multiplier" type="float">Multiplier</field>
         </message>
-        <message id="24" name="SET_COOLING_TIME_TC">
-            <description>Sets the time in ms that the system will wait before disarming after firing</description>
-            <field name="timing" type="uint32_t" units="ms">Timing in [ms]</field>
+        <message id="63" name="SET_ANTENNA_COORDINATES_ARP_TC">
+            <description>Sets current antennas coordinates</description>
+            <field name="latitude" type="float" units="deg">Latitude</field>
+            <field name="longitude" type="float" units="deg">Longitude</field>
+            <field name="height" type="float" units="m">Height</field>
+        </message>
+        <message id="64" name="SET_ROCKET_COORDINATES_ARP_TC">
+            <description>Sets current rocket coordinates</description>
+            <field name="latitude" type="float" units="deg">Latitude</field>
+            <field name="longitude" type="float" units="deg">Longitude</field>
+            <field name="height" type="float" units="m">Height</field>
+        </message>
+        <message id="65" name="ARP_COMMAND_TC">
+            <description>TC containing a command with no parameters that trigger some action</description>
+            <field name="command_id" type="uint8_t">A member of the MavArpCommandList enum</field>
         </message>
 
         <!-- FROM ROCKET TO GROUND: GENERIC -->
         <message id="100" name="ACK_TM">
-            <description>TM containing an ACK message to notify that the message has been received</description>
+            <description>TM containing an ACK message to notify that the message has been processed correctly</description>
             <field name="recv_msgid" type="uint8_t">Message id of the received message</field>
             <field name="seq_ack" type="uint8_t">Sequence number of the received message</field>
         </message>
@@ -365,8 +407,15 @@
             <description>TM containing a NACK message to notify that the received message was invalid</description>
             <field name="recv_msgid" type="uint8_t">Message id of the received message</field>
             <field name="seq_ack" type="uint8_t">Sequence number of the received message</field>
+            <field name="err_id" type="uint16_t">Error core that generated the NACK</field>
         </message>
-        <message id="102" name="GPS_TM">
+        <message id="102" name="WACK_TM">
+            <description>TM containing an ACK message to notify that the message has been processed with a warning</description>
+            <field name="recv_msgid" type="uint8_t">Message id of the received message</field>
+            <field name="seq_ack" type="uint8_t">Sequence number of the received message</field>
+            <field name="err_id" type="uint16_t">Error core that generated the WACK</field>
+        </message>
+        <message id="103" name="GPS_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">When was this logged</field>
             <field name="sensor_name" type="char[20]">Sensor name</field>
@@ -381,7 +430,7 @@
             <field name="track" type="float" units="deg">Track</field>
             <field name="n_satellites" type="uint8_t">Number of connected satellites</field>
         </message>
-        <message id="103" name="IMU_TM">
+        <message id="104" name="IMU_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">When was this logged</field>
             <field name="sensor_name" type="char[20]">Sensor name</field>
@@ -395,13 +444,13 @@
             <field name="mag_y" type="float" units="uT">Y axis compass</field>
             <field name="mag_z" type="float" units="uT">Z axis compass</field>
         </message>
-        <message id="104" name="PRESSURE_TM">
+        <message id="105" name="PRESSURE_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">When was this logged</field>
             <field name="sensor_name" type="char[20]">Sensor name</field>
             <field name="pressure" type="float" units="Pa">Pressure of the digital barometer</field>
         </message>
-        <message id="105" name="ADC_TM">
+        <message id="106" name="ADC_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">When was this logged</field>
             <field name="sensor_name" type="char[20]">Sensor name</field>
@@ -414,31 +463,31 @@
             <field name="channel_6" type="float" units="V">ADC voltage measured on channel 6</field>
             <field name="channel_7" type="float" units="V">ADC voltage measured on channel 7</field>
         </message>
-        <message id="106" name="VOLTAGE_TM">
+        <message id="107" name="VOLTAGE_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">When was this logged</field>
             <field name="sensor_name" type="char[20]">Sensor name</field>
             <field name="voltage" type="float" units="V">Voltage</field>
         </message>
-        <message id="107" name="CURRENT_TM">
+        <message id="108" name="CURRENT_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">When was this logged</field>
             <field name="sensor_name" type="char[20]">Sensor name</field>
             <field name="current" type="float" units="A">Current</field>
         </message>
-        <message id="108" name="TEMP_TM">
+        <message id="109" name="TEMP_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">When was this logged</field>
             <field name="sensor_name" type="char[20]">Sensor name</field>
             <field name="temperature" type="float" units="deg">Temperature</field>
         </message>
-        <message id="109" name="LOAD_TM">
+        <message id="110" name="LOAD_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">When was this logged</field>
             <field name="sensor_name" type="char[20]">Sensor name</field>
             <field name="load" type="float" units="kg">Load force</field>
         </message>
-        <message id="110" name="ATTITUDE_TM">
+        <message id="111" name="ATTITUDE_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">When was this logged</field>
             <field name="sensor_name" type="char[20]">Sensor name</field>
@@ -450,17 +499,18 @@
             <field name="quat_z" type="float">Quaternion z component</field>
             <field name="quat_w" type="float">Quaternion w component</field>
         </message>
-        <message id="111" name="SENSOR_STATE_TM">
+        <message id="112" name="SENSOR_STATE_TM">
             <description></description>
             <field name="sensor_name" type="char[20]">Sensor name</field>
-            <field name="state" type="uint8_t">Boolean that represents the init state</field>
+            <field name="initialized" type="uint8_t">Boolean that represents the init state</field>
+            <field name="enabled" type="uint8_t">Boolean that represents the enabled state</field>
         </message>
-        <message id="112" name="SERVO_TM">
+        <message id="113" name="SERVO_TM">
             <description></description>
             <field name="servo_id" type="uint8_t">A member of the ServosList enum</field>
             <field name="servo_position" type="float">Position of the servo [0-1]</field>
         </message>
-        <message id="113" name="PIN_TM">
+        <message id="114" name="PIN_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp</field>
             <field name="pin_id" type="uint8_t">A member of the PinsList enum</field>
@@ -468,21 +518,21 @@
             <field name="changes_counter" type="uint8_t">Number of changes of pin</field>
             <field name="current_state" type="uint8_t">Current state of pin</field>
         </message>
-        <message id="114" name="REGISTRY_FLOAT_TM">
+        <message id="115" name="REGISTRY_FLOAT_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp</field>
             <field name="key_id" type="uint32_t">Id of this configuration entry</field>
             <field name="key_name" type="char[20]">Name of this configuration entry</field>
             <field name="value" type="float">Value of this configuration</field>
         </message>
-        <message id="115" name="REGISTRY_INT_TM">
+        <message id="116" name="REGISTRY_INT_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp</field>
             <field name="key_id" type="uint32_t">Id of this configuration entry</field>
             <field name="key_name" type="char[20]">Name of this configuration entry</field>
             <field name="value" type="uint32_t">Value of this configuration</field>
         </message>
-        <message id="116" name="REGISTRY_COORD_TM">
+        <message id="117" name="REGISTRY_COORD_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp</field>
             <field name="key_id" type="uint32_t">Id of this configuration entry</field>
@@ -490,34 +540,9 @@
             <field name="latitude" type="float" units="deg">Latitude in this configuration</field>
             <field name="longitude" type="float" units="deg">Latitude in this configuration</field>
         </message>
-
-        <!-- FROM RECEIVER TO GROUNDSTATION -->
-        <message id="150" name="RECEIVER_TM">
-            <description></description>
-            <field name="timestamp" type="uint64_t" units="us">Timestamp</field>
-            <field name="main_radio_present" type="uint8_t">Boolean indicating the presence of the main radio</field>
-            <field name="main_packet_tx_error_count" type="uint16_t">Number of errors during send</field>
-            <field name="main_tx_bitrate" type="uint16_t" units="b/s">Send bitrate</field>
-            <field name="main_packet_rx_success_count" type="uint16_t">Number of succesfull received mavlink packets</field>
-            <field name="main_packet_rx_drop_count" type="uint16_t">Number of dropped mavlink packets</field>
-            <field name="main_rx_bitrate" type="uint16_t" units="b/s">Receive bitrate</field>
-            <field name="main_rx_rssi" type="float" units="dBm">Receive RSSI</field>
-            <field name="main_rx_fei" type="float" units="Hz">Receive frequency error index</field>
-            <field name="payload_radio_present" type="uint8_t">Boolean indicating the presence of the payload radio</field>
-            <field name="payload_packet_tx_error_count" type="uint16_t">Number of errors during send</field>
-            <field name="payload_tx_bitrate" type="uint16_t" units="b/s">Send bitrate</field>
-            <field name="payload_packet_rx_success_count" type="uint16_t">Number of succesfull received mavlink packets</field>
-            <field name="payload_packet_rx_drop_count" type="uint16_t">Number of dropped mavlink packets</field>
-            <field name="payload_rx_bitrate" type="uint16_t" units="b/s">Receive bitrate</field>
-            <field name="payload_rx_rssi" type="float" units="dBm">Receive RSSI</field>
-            <field name="payload_rx_fei" type="float" units="Hz">Receive frequency error index</field>
-            <field name="ethernet_present" type="uint8_t">Boolean indicating the presence of the ethernet module</field>
-            <field name="ethernet_status" type="uint8_t">Status flag indicating the status of the ethernet PHY</field>
-            <field name="battery_voltage" type="float" units="V">Battery voltage</field>
-        </message>
         
         <!-- FROM AUTOMATED ROCKET POINTER TO GROUNDSTATION -->
-        <message id="169" name="ARP_TM">
+        <message id="150" name="ARP_TM">
             <description></description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp</field>
             <field name="yaw" type="float" units="deg">Current Yaw</field>
@@ -542,20 +567,17 @@
             <field name="main_packet_rx_drop_count" type="uint16_t">Number of dropped mavlink packets</field>
             <field name="main_rx_bitrate" type="uint16_t" units="b/s">Receive bitrate</field>
             <field name="main_rx_rssi" type="float" units="dBm">Receive RSSI</field>
+            <field name="payload_radio_present" type="uint8_t">Boolean indicating the presence of the payload radio</field>
+            <field name="payload_packet_tx_error_count" type="uint16_t">Number of errors during send</field>
+            <field name="payload_tx_bitrate" type="uint16_t" units="b/s">Send bitrate</field>
+            <field name="payload_packet_rx_success_count" type="uint16_t">Number of succesfull received mavlink packets</field>
+            <field name="payload_packet_rx_drop_count" type="uint16_t">Number of dropped mavlink packets</field>
+            <field name="payload_rx_bitrate" type="uint16_t" units="b/s">Receive bitrate</field>
+            <field name="payload_rx_rssi" type="float" units="dBm">Receive RSSI</field>
             <field name="ethernet_present" type="uint8_t">Boolean indicating the presence of the ethernet module</field>
             <field name="ethernet_status" type="uint8_t">Status flag indicating the status of the ethernet PHY</field>
             <field name="battery_voltage" type="float" units="V">Battery voltage</field>
         </message>
-        <message id="170" name="SET_ANTENNA_COORDINATES_ARP_TC">
-            <description>Sets current antennas coordinates</description>
-            <field name="latitude" type="float" units="deg">Latitude</field>
-            <field name="longitude" type="float" units="deg">Longitude</field>
-        </message>
-        <message id="171" name="SET_ROCKET_COORDINATES_ARP_TC">
-            <description>Sets current rocket coordinates</description>
-            <field name="latitude" type="float" units="deg">Latitude</field>
-            <field name="longitude" type="float" units="deg">Longitude</field>
-        </message>
 
         <!-- FROM ROCKET TO GROUND: SPECIFIC -->
         <message id="200" name="SYS_TM">
@@ -564,21 +586,13 @@
             <field name="logger" type="uint8_t">True if the logger started correctly</field>
             <field name="event_broker" type="uint8_t">True if the event broker started correctly</field>
             <field name="radio" type="uint8_t">True if the radio started correctly</field>
-            <field name="pin_observer" type="uint8_t">True if the pin observer started correctly</field>
             <field name="sensors" type="uint8_t">True if the sensors started correctly</field>
-            <field name="board_scheduler" type="uint8_t">True if the board scheduler is running</field>
+            <field name="actuators" type="uint8_t">True if the sensors started correctly</field>
+            <field name="pin_handler" type="uint8_t">True if the pin observer started correctly</field>
+            <field name="can_handler" type="uint8_t">True if the can handler started correctly</field>
+            <field name="scheduler" type="uint8_t">True if the board scheduler is running</field>
         </message>
-        <message id="201" name="FSM_TM">
-            <description>Flight State Machine status telemetry</description>
-            <field name="timestamp" type="uint64_t" units="us">Timestamp</field>
-            <field name="ada_state" type="uint8_t">Apogee Detection Algorithm state</field>
-            <field name="abk_state" type="uint8_t">Air Brakes state</field>
-            <field name="dpl_state" type="uint8_t">Deployment state</field>
-            <field name="fmm_state" type="uint8_t">Flight Mode Manager state</field>
-            <field name="nas_state" type="uint8_t">Navigation and Attitude System state</field>
-            <field name="wes_state" type="uint8_t">Wind Estimation System state</field>
-        </message>
-        <message id="202" name="LOGGER_TM">
+        <message id="201" name="LOGGER_TM">
             <description>Logger status telemetry</description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp</field>
             <field name="log_number" type="int16_t">Currently active log file, -1 if the logger is inactive</field>
@@ -592,8 +606,8 @@
             <field name="average_write_time" type="int32_t">Average time to perform an fwrite() of a buffer</field>
             <field name="max_write_time" type="int32_t">Max time to perform an fwrite() of a buffer</field>
         </message>
-        <message id="203" name="MAVLINK_STATS_TM">
-            <description>Status of the TMTCManager telemetry</description>
+        <message id="202" name="MAVLINK_STATS_TM">
+            <description>Status of MavlinkDriver</description>
             <field name="timestamp" type="uint64_t" units="us">When was this logged </field>
             <field name="n_send_queue" type="uint16_t">Current len of the occupied portion of the queue</field>
             <field name="max_send_queue" type="uint16_t">Max occupied len of the queue </field>
@@ -608,15 +622,26 @@
             <field name="packet_rx_success_count" type="uint16_t"> Received packets</field>
             <field name="packet_rx_drop_count" type="uint16_t">  Number of packet drops   </field>
         </message>
+        <message id="203" name="CAN_STATS_TM">
+            <description>Status of CanHandler</description>
+            <field name="timestamp" type="uint64_t" units="us">When was this logged</field>
+            <field name="payload_bit_rate" type="float">Payload only bitrate</field>
+            <field name="total_bit_rate" type="float">Total bitrate</field>
+            <field name="load_percent" type="float">Load percent of the BUS</field>
+        </message>
         <message id="204" name="TASK_STATS_TM">
             <description>Statistics of the Task Scheduler</description>
             <field name="timestamp" type="uint64_t" units="us">When was this logged </field>
-            <field name="task_id" type="uint8_t">Task ID</field>
-            <field name="task_period" type="uint16_t" units="ms">Period of the task</field>
-            <field name="task_min" type="float">Task min period</field>
-            <field name="task_max" type="float">Task max period</field>
-            <field name="task_mean" type="float">Task mean period</field>
-            <field name="task_stddev" type="float">Task period std deviation</field>
+            <field name="task_id" type="uint16_t">Task ID</field>
+            <field name="task_period" type="uint16_t" units="ns">Period of the task</field>
+            <field name="task_missed_events" type="uint32_t">Number of missed events</field>
+            <field name="task_failed_events" type="uint32_t">Number of missed events</field>
+            <field name="task_activation_mean" type="float">Task activation mean period</field>
+            <field name="task_activation_stddev" type="float">Task activation mean standard deviation</field>
+            <field name="task_period_mean" type="float">Task period mean period</field>
+            <field name="task_period_stddev" type="float">Task period mean standard deviation</field>
+            <field name="task_workload_mean" type="float">Task workload mean period</field>
+            <field name="task_workload_stddev" type="float">Task workload mean standard deviation</field>
         </message>
         <message id="205" name="ADA_TM">
             <description>Apogee Detection Algorithm status telemetry</description>
@@ -664,7 +689,7 @@
             <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>
+            <field name="corrected_pressure" type="float" units="Pa">Corrected pressure</field>
         </message>
         <message id="208" name="ROCKET_FLIGHT_TM">
             <description>High Rate Telemetry</description>
@@ -673,7 +698,7 @@
             <field name="fmm_state" type="uint8_t">Flight Mode Manager State</field>
             <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="nas_state" type="uint8_t">NAS 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>
@@ -697,35 +722,32 @@
             <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="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>
-            <field name="nas_vn" type="float" units="m/s">Navigation system estimated north velocity</field>
-            <field name="nas_ve" type="float" units="m/s">Navigation system estimated east velocity</field>
-            <field name="nas_vd" type="float" units="m/s">Navigation system estimated down velocity</field>
-            <field name="nas_qx" type="float" units="deg">Navigation system estimated attitude (qx)</field>
-            <field name="nas_qy" type="float" units="deg">Navigation system estimated attitude (qy)</field>
-            <field name="nas_qz" type="float" units="deg">Navigation system estimated attitude (qz)</field>
-            <field name="nas_qw" type="float" units="deg">Navigation system estimated attitude (qw)</field>
-            <field name="nas_bias_x" type="float">Navigation system gyroscope bias on x axis</field>
-            <field name="nas_bias_y" type="float">Navigation system gyroscope bias on y axis</field>
-            <field name="nas_bias_z" type="float">Navigation system gyroscope bias on z axis</field>
-            <field name="pin_quick_connector" type="float"> Quick connector detach pin </field>
+            <field name="nas_n" type="float" units="deg">NAS estimated noth position</field>
+            <field name="nas_e" type="float" units="deg">NAS estimated east position</field>
+            <field name="nas_d" type="float" units="m">NAS estimated down position</field>
+            <field name="nas_vn" type="float" units="m/s">NAS estimated north velocity</field>
+            <field name="nas_ve" type="float" units="m/s">NAS estimated east velocity</field>
+            <field name="nas_vd" type="float" units="m/s">NAS estimated down velocity</field>
+            <field name="nas_qx" type="float" units="deg">NAS estimated attitude (qx)</field>
+            <field name="nas_qy" type="float" units="deg">NAS estimated attitude (qy)</field>
+            <field name="nas_qz" type="float" units="deg">NAS estimated attitude (qz)</field>
+            <field name="nas_qw" type="float" units="deg">NAS estimated attitude (qw)</field>
+            <field name="nas_bias_x" type="float">NAS gyroscope bias on x axis</field>
+            <field name="nas_bias_y" type="float">NAS gyroscope bias on y axis</field>
+            <field name="nas_bias_z" type="float">NAS gyroscope bias on z axis</field>
             <field name="pin_launch" type="uint8_t">Launch pin status (1 = connected, 0 = disconnected)</field>
             <field name="pin_nosecone" type="uint8_t">Nosecone pin status (1 = connected, 0 = disconnected)</field>
             <field name="pin_expulsion" type="uint8_t">Servo sensor status (1 = actuated, 0 = idle)</field>
             <field name="cutter_presence" type="uint8_t">Cutter presence status (1 = present, 0 = missing)</field>
             <field name="battery_voltage" type="float" units="V">Battery voltage</field>
             <field name="cam_battery_voltage" type="float" units="V">Camera battery voltage</field>
-            <field name="current_consumption" type="float" units="A">Battery current</field>
             <field name="temperature" type="float" units="degC">Temperature</field>
-            <field name="logger_error" type="int8_t">Logger error (0 = no error, -1 otherwise)</field>
         </message>
         <message id="209" name="PAYLOAD_FLIGHT_TM">
             <description>High Rate Telemetry</description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp in microseconds</field>
             <field name="fmm_state" type="uint8_t">Flight Mode Manager State</field>
-            <field name="nas_state" type="uint8_t">Navigation System FSM State</field>
+            <field name="nas_state" type="uint8_t">NAS FSM State</field>
             <field name="wes_state" type="uint8_t">Wind Estimation System FSM State</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>
@@ -746,28 +768,27 @@
             <field name="gps_alt" type="float" units="m">GPS Altitude</field>
             <field name="left_servo_angle" type="float" units="deg">Left servo motor angle</field>
             <field name="right_servo_angle" type="float" units="deg">Right servo motor angle</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>
-            <field name="nas_vn" type="float" units="m/s">Navigation system estimated north velocity</field>
-            <field name="nas_ve" type="float" units="m/s">Navigation system estimated east velocity</field>
-            <field name="nas_vd" type="float" units="m/s">Navigation system estimated down velocity</field>
-            <field name="nas_qx" type="float" units="deg">Navigation system estimated attitude (qx)</field>
-            <field name="nas_qy" type="float" units="deg">Navigation system estimated attitude (qy)</field>
-            <field name="nas_qz" type="float" units="deg">Navigation system estimated attitude (qz)</field>
-            <field name="nas_qw" type="float" units="deg">Navigation system estimated attitude (qw)</field>
-            <field name="nas_bias_x" type="float">Navigation system gyroscope bias on x axis</field>
-            <field name="nas_bias_y" type="float">Navigation system gyroscope bias on y axis</field>
-            <field name="nas_bias_z" type="float">Navigation system gyroscope bias on z axis</field>
+            <field name="nas_n" type="float" units="deg">NAS estimated noth position</field>
+            <field name="nas_e" type="float" units="deg">NAS estimated east position</field>
+            <field name="nas_d" type="float" units="m">NAS estimated down position</field>
+            <field name="nas_vn" type="float" units="m/s">NAS estimated north velocity</field>
+            <field name="nas_ve" type="float" units="m/s">NAS estimated east velocity</field>
+            <field name="nas_vd" type="float" units="m/s">NAS estimated down velocity</field>
+            <field name="nas_qx" type="float" units="deg">NAS estimated attitude (qx)</field>
+            <field name="nas_qy" type="float" units="deg">NAS estimated attitude (qy)</field>
+            <field name="nas_qz" type="float" units="deg">NAS estimated attitude (qz)</field>
+            <field name="nas_qw" type="float" units="deg">NAS estimated attitude (qw)</field>
+            <field name="nas_bias_x" type="float">NAS gyroscope bias on x axis</field>
+            <field name="nas_bias_y" type="float">NAS gyroscope bias on y axis</field>
+            <field name="nas_bias_z" type="float">NAS gyroscope bias on z axis</field>
             <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_launch" type="uint8_t">Launch pin status (1 = connected, 0 = disconnected)</field>
             <field name="pin_nosecone" type="uint8_t">Nosecone pin status (1 = connected, 0 = disconnected)</field>
+            <field name="cutter_presence" type="uint8_t">Cutter presence status (1 = present, 0 = missing)</field>
             <field name="battery_voltage" type="float" units="V">Battery voltage</field>
             <field name="cam_battery_voltage" type="float" units="V">Camera battery voltage</field>
-            <field name="current_consumption" type="float" units="A">Battery current</field>
-            <field name="cutter_presence" type="uint8_t">Cutter presence status (1 = present, 0 = missing)</field>
             <field name="temperature" type="float" units="degC">Temperature</field>
-            <field name="logger_error" type="int8_t">Logger error (0 = no error)</field>
         </message>
         <message id="210" name="ROCKET_STATS_TM">
             <description>Low Rate Telemetry</description>
@@ -786,9 +807,17 @@
             <field name="apogee_alt" type="float" units="m">Apogee altitude</field>
             <field name="min_pressure" type="float" units="Pa">Apogee pressure - Digital barometer</field>
             <field name="ada_min_pressure" type="float" units="Pa">Apogee pressure - ADA filtered</field>
-            <field name="dpl_vane_max_pressure" type="float" units="Pa">Max pressure in the deployment bay during drogue deployment</field>
+            <field name="dpl_bay_max_pressure" type="float" units="Pa">Max pressure in the deployment bay during drogue deployment</field>
             <field name="cpu_load" type="float">CPU load in percentage</field>
             <field name="free_heap" type="uint32_t">Amount of available heap in memory</field>
+            <field name="log_number" type="int16_t">Currently active log file, -1 if the logger is inactive</field>
+            <field name="log_good" type="int32_t">0 if log failed, 1 otherwise</field>
+            <field name="payload_board_state" type="uint8_t">Main board fmm state</field>
+            <field name="motor_board_state" type="uint8_t">Motor board fmm state</field>
+            <field name="payload_can_status" type="uint8_t">Main CAN status</field>
+            <field name="motor_can_status" type="uint8_t">Motor CAN status</field>
+            <field name="rig_can_status" type="uint8_t">RIG CAN status</field>
+            <field name="hil_state" type="uint8_t">1 if the board is currently in HIL mode</field>
         </message>
         <message id="211" name="PAYLOAD_STATS_TM">
             <description>Low Rate Telemetry</description>
@@ -807,6 +836,14 @@
             <field name="min_pressure" type="float" units="Pa">Apogee pressure - Digital barometer</field>
             <field name="cpu_load" type="float">CPU load in percentage</field>
             <field name="free_heap" type="uint32_t">Amount of available heap in memory</field>
+            <field name="log_number" type="int16_t">Currently active log file, -1 if the logger is inactive</field>
+            <field name="log_good" type="int32_t">0 if log failed, 1 otherwise</field>
+            <field name="main_board_state" type="uint8_t">Main board fmm state</field>
+            <field name="motor_board_state" type="uint8_t">Motor board fmm state</field>
+            <field name="main_can_status" type="uint8_t">Main CAN status</field>
+            <field name="motor_can_status" type="uint8_t">Motor CAN status</field>
+            <field name="rig_can_status" type="uint8_t">RIG CAN status</field>
+            <field name="hil_state" type="uint8_t">1 if the board is currently in HIL mode</field>
         </message>
         <message id="212" name="GSE_TM">
             <description>Ground Segment Equipment telemetry</description>
@@ -815,19 +852,25 @@
             <field name="loadcell_vessel" type="float" units="kg">External tank weight</field>
             <field name="filling_pressure" type="float" units="Bar">Refueling line pressure</field>
             <field name="vessel_pressure" type="float" units="Bar">Vessel tank pressure</field>
-            <field name="arming_state" type="uint8_t">1 If the rocket is armed</field>
             <field name="filling_valve_state" type="uint8_t">1 If the filling valve is open</field>
             <field name="venting_valve_state" type="uint8_t">1 If the venting valve is open</field>
             <field name="release_valve_state" type="uint8_t">1 If the release valve is open</field>
             <field name="main_valve_state" type="uint8_t">1 If the main valve is open</field>
             <field name="nitrogen_valve_state" type="uint8_t"> 1 If the nitrogen valve is open</field>
             <field name="gmm_state" type="uint8_t">State of the GroundModeManager</field>
-            <field name="tars_state" type="uint8_t">1 If the TARS algorithm is running</field>
+            <field name="tars_state" type="uint8_t">State of Tars</field>
+            <field name="arming_state" type="uint8_t">Arming state (1 if armed, 0 otherwise)</field>
             <field name="battery_voltage" type="float">Battery voltage</field>
-            <field name="current_consumption" type="float"> RIG current </field>
-            <field name="main_board_status" type="uint8_t"> MAIN board status [0: not present, 1: online, 2: armed]</field>
-            <field name="payload_board_status" type="uint8_t"> PAYLOAD board status [0: not present, 1: online, 2: armed]</field>
-            <field name="motor_board_status" type="uint8_t"> MOTOR board status [0: not present, 1: online, 2: armed]</field>
+            <field name="current_consumption" type="float" units="A">RIG current</field>
+            <field name="umbilical_current_consumption" type="float" units="A">Umbilical current</field>
+            <field name="main_board_state" type="uint8_t">Main board fmm state</field>
+            <field name="payload_board_state" type="uint8_t">Payload board fmm state</field>
+            <field name="motor_board_state" type="uint8_t">Motor board fmm state</field>
+            <field name="main_can_status" type="uint8_t">Main CAN status</field>
+            <field name="payload_can_status" type="uint8_t">Payload CAN status</field>
+            <field name="motor_can_status" type="uint8_t">Motor CAN status</field>
+            <field name="log_number" type="int16_t">Currently active log file, -1 if the logger is inactive</field>
+            <field name="log_good" type="int32_t">0 if log failed, 1 otherwise</field>
         </message>
         <message id="213" name="MOTOR_TM">
             <description>Motor rocket telemetry</description>
@@ -839,7 +882,9 @@
             <field name="main_valve_state" type="uint8_t">1 If the main valve is open </field>
             <field name="venting_valve_state" type="uint8_t">1 If the venting 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>
+            <field name="log_number" type="int16_t">Currently active log file, -1 if the logger is inactive</field>
+            <field name="log_good" type="int32_t">0 if log failed, 1 otherwise</field>
+            <field name="hil_state" type="uint8_t">1 if the board is currently in HIL mode</field>
         </message>
     </messages>
 </mavlink>