diff --git a/mavlink_lib.py b/mavlink_lib.py
index 2c57eac58b920a3f3cf55f31f402de84c93f95ae..542871538c62d25accf59f604b2a1fbf0f389111 100644
--- a/mavlink_lib.py
+++ b/mavlink_lib.py
@@ -2674,7 +2674,7 @@ class MAVLink_mea_tm_message(MAVLink_message):
 
 class MAVLink_rocket_flight_tm_message(MAVLink_message):
         '''
-        High Rate Telemetry
+        High Rate Rocket Telemetry
         '''
         id = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM
         name = 'ROCKET_FLIGHT_TM'
@@ -2750,27 +2750,27 @@ class MAVLink_rocket_flight_tm_message(MAVLink_message):
 
 class MAVLink_payload_flight_tm_message(MAVLink_message):
         '''
-        High Rate Telemetry
+        High Rate Payload Telemetry
         '''
         id = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM
         name = 'PAYLOAD_FLIGHT_TM'
-        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_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'fmm_state', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'battery_voltage', 'cam_battery_voltage', 'temperature']
-        ordered_fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'battery_voltage', 'cam_battery_voltage', 'temperature', 'gps_fix', 'fmm_state']
-        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
+        fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'pressure_dynamic', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'fmm_state', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'battery_voltage', 'cam_battery_voltage', 'temperature']
+        ordered_fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'pressure_dynamic', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'battery_voltage', 'cam_battery_voltage', 'temperature', 'gps_fix', 'fmm_state']
+        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "pressure_digi": "Pa", "pressure_static": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "left_servo_angle": "deg", "right_servo_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "wes_n": "m/s", "wes_e": "m/s", "battery_voltage": "V", "cam_battery_voltage": "V", "temperature": "degC"}
-        format = '<QffffffffffffffffffffffffffffffffffffBB'
-        native_format = bytearray('<QffffffffffffffffffffffffffffffffffffBB', 'ascii')
-        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 37, 14, 15, 16, 38, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 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]
-        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]
-        crc_extra = 138
-        unpacker = struct.Struct('<QffffffffffffffffffffffffffffffffffffBB')
+        fieldunits_by_name = {"timestamp": "us", "pressure_digi": "Pa", "pressure_static": "Pa", "pressure_dynamic": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "left_servo_angle": "deg", "right_servo_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "wes_n": "m/s", "wes_e": "m/s", "battery_voltage": "V", "cam_battery_voltage": "V", "temperature": "degC"}
+        format = '<QfffffffffffffffffffffffffffffffffffffBB'
+        native_format = bytearray('<QfffffffffffffffffffffffffffffffffffffBB', 'ascii')
+        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 38, 15, 16, 17, 39, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37]
+        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 188
+        unpacker = struct.Struct('<QfffffffffffffffffffffffffffffffffffffBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, battery_voltage, cam_battery_voltage, temperature):
+        def __init__(self, timestamp, pressure_digi, pressure_static, pressure_dynamic, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, battery_voltage, cam_battery_voltage, temperature):
                 MAVLink_message.__init__(self, MAVLink_payload_flight_tm_message.id, MAVLink_payload_flight_tm_message.name)
                 self._fieldnames = MAVLink_payload_flight_tm_message.fieldnames
                 self._instance_field = MAVLink_payload_flight_tm_message.instance_field
@@ -2778,6 +2778,7 @@ class MAVLink_payload_flight_tm_message(MAVLink_message):
                 self.timestamp = timestamp
                 self.pressure_digi = pressure_digi
                 self.pressure_static = pressure_static
+                self.pressure_dynamic = pressure_dynamic
                 self.airspeed_pitot = airspeed_pitot
                 self.altitude_agl = altitude_agl
                 self.acc_x = acc_x
@@ -2816,11 +2817,11 @@ class MAVLink_payload_flight_tm_message(MAVLink_message):
                 self.temperature = temperature
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 138, struct.pack('<QffffffffffffffffffffffffffffffffffffBB', 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.gps_fix, self.fmm_state), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 188, struct.pack('<QfffffffffffffffffffffffffffffffffffffBB', self.timestamp, self.pressure_digi, self.pressure_static, self.pressure_dynamic, self.airspeed_pitot, self.altitude_agl, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.left_servo_angle, self.right_servo_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.wes_n, self.wes_e, self.battery_voltage, self.cam_battery_voltage, self.temperature, self.gps_fix, self.fmm_state), force_mavlink1=force_mavlink1)
 
 class MAVLink_rocket_stats_tm_message(MAVLink_message):
         '''
-        Low Rate Telemetry
+        Low Rate Rocket Telemetry
         '''
         id = MAVLINK_MSG_ID_ROCKET_STATS_TM
         name = 'ROCKET_STATS_TM'
@@ -2896,31 +2897,32 @@ class MAVLink_rocket_stats_tm_message(MAVLink_message):
 
 class MAVLink_payload_stats_tm_message(MAVLink_message):
         '''
-        Low Rate Telemetry
+        Low Rate Payload Telemetry
         '''
         id = MAVLINK_MSG_ID_PAYLOAD_STATS_TM
         name = 'PAYLOAD_STATS_TM'
-        fieldnames = ['liftoff_ts', 'liftoff_max_acc_ts', 'liftoff_max_acc', 'max_speed_ts', 'max_speed', 'max_speed_altitude', 'max_mach_ts', 'max_mach', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'apogee_max_acc_ts', 'apogee_max_acc', 'wing_emc_n', 'wing_emc_e', 'wing_m1_n', 'wing_m1_e', 'wing_m2_n', 'wing_m2_e', 'dpl_ts', 'dpl_alt', 'dpl_max_acc_ts', 'dpl_max_acc', 'ref_lat', 'ref_lon', 'ref_alt', 'min_pressure', 'cpu_load', 'free_heap', 'nas_state', 'wes_state', 'pin_launch', 'pin_nosecone', 'cutter_presence', 'log_number', 'log_good', 'main_board_state', 'motor_board_state', 'main_can_status', 'motor_can_status', 'rig_can_status', 'hil_state']
-        ordered_fieldnames = ['liftoff_ts', 'liftoff_max_acc_ts', 'max_speed_ts', 'max_mach_ts', 'apogee_ts', 'apogee_max_acc_ts', 'dpl_ts', 'dpl_max_acc_ts', 'liftoff_max_acc', 'max_speed', 'max_speed_altitude', 'max_mach', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'apogee_max_acc', 'wing_emc_n', 'wing_emc_e', 'wing_m1_n', 'wing_m1_e', 'wing_m2_n', 'wing_m2_e', 'dpl_alt', 'dpl_max_acc', 'ref_lat', 'ref_lon', 'ref_alt', 'min_pressure', 'cpu_load', 'free_heap', 'log_good', 'log_number', 'nas_state', 'wes_state', 'pin_launch', 'pin_nosecone', 'cutter_presence', 'main_board_state', 'motor_board_state', 'main_can_status', 'motor_can_status', 'rig_can_status', 'hil_state']
-        fieldtypes = ['uint64_t', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'uint32_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'int16_t', 'int32_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
+        fieldnames = ['timestamp', 'liftoff_ts', 'liftoff_max_acc_ts', 'liftoff_max_acc', 'max_speed_ts', 'max_speed', 'max_speed_altitude', 'max_mach_ts', 'max_mach', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'apogee_max_acc_ts', 'apogee_max_acc', 'wing_target_lat', 'wing_target_lon', 'wing_active_target_n', 'wing_active_target_e', 'wing_algorithm', 'dpl_ts', 'dpl_alt', 'dpl_max_acc_ts', 'dpl_max_acc', 'ref_lat', 'ref_lon', 'ref_alt', 'min_pressure', 'cpu_load', 'free_heap', 'nas_state', 'wnc_state', 'pin_launch', 'pin_nosecone', 'cutter_presence', 'log_number', 'log_good', 'main_board_state', 'motor_board_state', 'main_can_status', 'motor_can_status', 'rig_can_status', 'hil_state']
+        ordered_fieldnames = ['timestamp', 'liftoff_ts', 'liftoff_max_acc_ts', 'max_speed_ts', 'max_mach_ts', 'apogee_ts', 'apogee_max_acc_ts', 'dpl_ts', 'dpl_max_acc_ts', 'liftoff_max_acc', 'max_speed', 'max_speed_altitude', 'max_mach', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'apogee_max_acc', 'wing_target_lat', 'wing_target_lon', 'wing_active_target_n', 'wing_active_target_e', 'dpl_alt', 'dpl_max_acc', 'ref_lat', 'ref_lon', 'ref_alt', 'min_pressure', 'cpu_load', 'free_heap', 'log_good', 'log_number', 'wing_algorithm', 'nas_state', 'wnc_state', 'pin_launch', 'pin_nosecone', 'cutter_presence', 'main_board_state', 'motor_board_state', 'main_can_status', 'motor_can_status', 'rig_can_status', 'hil_state']
+        fieldtypes = ['uint64_t', 'uint64_t', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'uint32_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'int16_t', 'int32_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"liftoff_ts": "us", "liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "max_speed_ts": "us", "max_speed": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "apogee_max_acc_ts": "us", "apogee_max_acc": "m/s2", "wing_emc_n": "m", "wing_emc_e": "m", "wing_m1_n": "m", "wing_m1_e": "m", "wing_m2_n": "m", "wing_m2_e": "m", "dpl_ts": "us", "dpl_alt": "m", "dpl_max_acc_ts": "us", "dpl_max_acc": "m/s2", "ref_lat": "deg", "ref_lon": "deg", "ref_alt": "m", "min_pressure": "Pa"}
-        format = '<QQQQQQQQfffffffffffffffffffffIihBBBBBBBBBBB'
-        native_format = bytearray('<QQQQQQQQfffffffffffffffffffffIihBBBBBBBBBBB', 'ascii')
-        orders = [0, 1, 8, 2, 9, 10, 3, 11, 4, 12, 13, 14, 5, 15, 16, 17, 18, 19, 20, 21, 6, 22, 7, 23, 24, 25, 26, 27, 28, 29, 32, 33, 34, 35, 36, 31, 30, 37, 38, 39, 40, 41, 42]
+        fieldunits_by_name = {"timestamp": "us", "liftoff_ts": "us", "liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "max_speed_ts": "us", "max_speed": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "apogee_max_acc_ts": "us", "apogee_max_acc": "m/s2", "wing_target_lat": "deg", "wing_target_lon": "deg", "wing_active_target_n": "m", "wing_active_target_e": "m", "dpl_ts": "us", "dpl_alt": "m", "dpl_max_acc_ts": "us", "dpl_max_acc": "m/s2", "ref_lat": "deg", "ref_lon": "deg", "ref_alt": "m", "min_pressure": "Pa"}
+        format = '<QQQQQQQQQfffffffffffffffffffIihBBBBBBBBBBBB'
+        native_format = bytearray('<QQQQQQQQQfffffffffffffffffffIihBBBBBBBBBBBB', 'ascii')
+        orders = [0, 1, 2, 9, 3, 10, 11, 4, 12, 5, 13, 14, 15, 6, 16, 17, 18, 19, 20, 31, 7, 21, 8, 22, 23, 24, 25, 26, 27, 28, 32, 33, 34, 35, 36, 30, 29, 37, 38, 39, 40, 41, 42]
         lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
         array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-        crc_extra = 206
-        unpacker = struct.Struct('<QQQQQQQQfffffffffffffffffffffIihBBBBBBBBBBB')
+        crc_extra = 99
+        unpacker = struct.Struct('<QQQQQQQQQfffffffffffffffffffIihBBBBBBBBBBBB')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_emc_n, wing_emc_e, wing_m1_n, wing_m1_e, wing_m2_n, wing_m2_e, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wes_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state):
+        def __init__(self, timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_target_lat, wing_target_lon, wing_active_target_n, wing_active_target_e, wing_algorithm, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wnc_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state):
                 MAVLink_message.__init__(self, MAVLink_payload_stats_tm_message.id, MAVLink_payload_stats_tm_message.name)
                 self._fieldnames = MAVLink_payload_stats_tm_message.fieldnames
                 self._instance_field = MAVLink_payload_stats_tm_message.instance_field
                 self._instance_offset = MAVLink_payload_stats_tm_message.instance_offset
+                self.timestamp = timestamp
                 self.liftoff_ts = liftoff_ts
                 self.liftoff_max_acc_ts = liftoff_max_acc_ts
                 self.liftoff_max_acc = liftoff_max_acc
@@ -2935,12 +2937,11 @@ class MAVLink_payload_stats_tm_message(MAVLink_message):
                 self.apogee_alt = apogee_alt
                 self.apogee_max_acc_ts = apogee_max_acc_ts
                 self.apogee_max_acc = apogee_max_acc
-                self.wing_emc_n = wing_emc_n
-                self.wing_emc_e = wing_emc_e
-                self.wing_m1_n = wing_m1_n
-                self.wing_m1_e = wing_m1_e
-                self.wing_m2_n = wing_m2_n
-                self.wing_m2_e = wing_m2_e
+                self.wing_target_lat = wing_target_lat
+                self.wing_target_lon = wing_target_lon
+                self.wing_active_target_n = wing_active_target_n
+                self.wing_active_target_e = wing_active_target_e
+                self.wing_algorithm = wing_algorithm
                 self.dpl_ts = dpl_ts
                 self.dpl_alt = dpl_alt
                 self.dpl_max_acc_ts = dpl_max_acc_ts
@@ -2952,7 +2953,7 @@ class MAVLink_payload_stats_tm_message(MAVLink_message):
                 self.cpu_load = cpu_load
                 self.free_heap = free_heap
                 self.nas_state = nas_state
-                self.wes_state = wes_state
+                self.wnc_state = wnc_state
                 self.pin_launch = pin_launch
                 self.pin_nosecone = pin_nosecone
                 self.cutter_presence = cutter_presence
@@ -2966,7 +2967,7 @@ class MAVLink_payload_stats_tm_message(MAVLink_message):
                 self.hil_state = hil_state
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 206, struct.pack('<QQQQQQQQfffffffffffffffffffffIihBBBBBBBBBBB', self.liftoff_ts, self.liftoff_max_acc_ts, self.max_speed_ts, self.max_mach_ts, self.apogee_ts, self.apogee_max_acc_ts, self.dpl_ts, self.dpl_max_acc_ts, self.liftoff_max_acc, self.max_speed, self.max_speed_altitude, self.max_mach, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.apogee_max_acc, self.wing_emc_n, self.wing_emc_e, self.wing_m1_n, self.wing_m1_e, self.wing_m2_n, self.wing_m2_e, self.dpl_alt, self.dpl_max_acc, self.ref_lat, self.ref_lon, self.ref_alt, self.min_pressure, self.cpu_load, self.free_heap, self.log_good, self.log_number, self.nas_state, self.wes_state, self.pin_launch, self.pin_nosecone, self.cutter_presence, self.main_board_state, self.motor_board_state, self.main_can_status, self.motor_can_status, self.rig_can_status, self.hil_state), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 99, struct.pack('<QQQQQQQQQfffffffffffffffffffIihBBBBBBBBBBBB', self.timestamp, self.liftoff_ts, self.liftoff_max_acc_ts, self.max_speed_ts, self.max_mach_ts, self.apogee_ts, self.apogee_max_acc_ts, self.dpl_ts, self.dpl_max_acc_ts, self.liftoff_max_acc, self.max_speed, self.max_speed_altitude, self.max_mach, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.apogee_max_acc, self.wing_target_lat, self.wing_target_lon, self.wing_active_target_n, self.wing_active_target_e, self.dpl_alt, self.dpl_max_acc, self.ref_lat, self.ref_lon, self.ref_alt, self.min_pressure, self.cpu_load, self.free_heap, self.log_good, self.log_number, self.wing_algorithm, self.nas_state, self.wnc_state, self.pin_launch, self.pin_nosecone, self.cutter_presence, self.main_board_state, self.motor_board_state, self.main_can_status, self.motor_can_status, self.rig_can_status, self.hil_state), force_mavlink1=force_mavlink1)
 
 class MAVLink_gse_tm_message(MAVLink_message):
         '''
@@ -3071,23 +3072,23 @@ class MAVLink_calibration_tm_message(MAVLink_message):
         '''
         id = MAVLINK_MSG_ID_CALIBRATION_TM
         name = 'CALIBRATION_TM'
-        fieldnames = ['timestamp', 'gyro_bias_x', 'gyro_bias_y', 'gyro_bias_z', 'mag_bias_x', 'mag_bias_y', 'mag_bias_z', 'mag_scale_x', 'mag_scale_y', 'mag_scale_z', 'static_press_1_bias', 'static_press_1_scale', 'static_press_2_bias', 'static_press_2_scale', 'dpl_bay_press_bias', 'dpl_bay_press_scale']
-        ordered_fieldnames = ['timestamp', 'gyro_bias_x', 'gyro_bias_y', 'gyro_bias_z', 'mag_bias_x', 'mag_bias_y', 'mag_bias_z', 'mag_scale_x', 'mag_scale_y', 'mag_scale_z', 'static_press_1_bias', 'static_press_1_scale', 'static_press_2_bias', 'static_press_2_scale', 'dpl_bay_press_bias', 'dpl_bay_press_scale']
-        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
+        fieldnames = ['timestamp', 'gyro_bias_x', 'gyro_bias_y', 'gyro_bias_z', 'mag_bias_x', 'mag_bias_y', 'mag_bias_z', 'mag_scale_x', 'mag_scale_y', 'mag_scale_z', 'static_press_1_bias', 'static_press_1_scale', 'static_press_2_bias', 'static_press_2_scale', 'dpl_bay_press_bias', 'dpl_bay_press_scale', 'dynamic_press_bias', 'dynamic_press_scale']
+        ordered_fieldnames = ['timestamp', 'gyro_bias_x', 'gyro_bias_y', 'gyro_bias_z', 'mag_bias_x', 'mag_bias_y', 'mag_bias_z', 'mag_scale_x', 'mag_scale_y', 'mag_scale_z', 'static_press_1_bias', 'static_press_1_scale', 'static_press_2_bias', 'static_press_2_scale', 'dpl_bay_press_bias', 'dpl_bay_press_scale', 'dynamic_press_bias', 'dynamic_press_scale']
+        fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
         fielddisplays_by_name = {}
         fieldenums_by_name = {}
-        fieldunits_by_name = {"timestamp": "us", "gyro_bias_x": "deg/s", "gyro_bias_y": "deg/s", "gyro_bias_z": "deg/s", "mag_bias_x": "uT", "mag_bias_y": "uT", "mag_bias_z": "uT", "static_press_1_bias": "Pa", "static_press_2_bias": "Pa", "dpl_bay_press_bias": "Pa"}
-        format = '<Qfffffffffffffff'
-        native_format = bytearray('<Qfffffffffffffff', 'ascii')
-        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15]
-        lengths = [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]
-        crc_extra = 31
-        unpacker = struct.Struct('<Qfffffffffffffff')
+        fieldunits_by_name = {"timestamp": "us", "gyro_bias_x": "deg/s", "gyro_bias_y": "deg/s", "gyro_bias_z": "deg/s", "mag_bias_x": "uT", "mag_bias_y": "uT", "mag_bias_z": "uT", "static_press_1_bias": "Pa", "static_press_2_bias": "Pa", "dpl_bay_press_bias": "Pa", "dynamic_press_bias": "Pa"}
+        format = '<Qfffffffffffffffff'
+        native_format = bytearray('<Qfffffffffffffffff', 'ascii')
+        orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17]
+        lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
+        array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
+        crc_extra = 210
+        unpacker = struct.Struct('<Qfffffffffffffffff')
         instance_field = None
         instance_offset = -1
 
-        def __init__(self, timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale):
+        def __init__(self, timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale, dynamic_press_bias, dynamic_press_scale):
                 MAVLink_message.__init__(self, MAVLink_calibration_tm_message.id, MAVLink_calibration_tm_message.name)
                 self._fieldnames = MAVLink_calibration_tm_message.fieldnames
                 self._instance_field = MAVLink_calibration_tm_message.instance_field
@@ -3108,9 +3109,11 @@ class MAVLink_calibration_tm_message(MAVLink_message):
                 self.static_press_2_scale = static_press_2_scale
                 self.dpl_bay_press_bias = dpl_bay_press_bias
                 self.dpl_bay_press_scale = dpl_bay_press_scale
+                self.dynamic_press_bias = dynamic_press_bias
+                self.dynamic_press_scale = dynamic_press_scale
 
         def pack(self, mav, force_mavlink1=False):
-                return MAVLink_message.pack(self, mav, 31, struct.pack('<Qfffffffffffffff', self.timestamp, self.gyro_bias_x, self.gyro_bias_y, self.gyro_bias_z, self.mag_bias_x, self.mag_bias_y, self.mag_bias_z, self.mag_scale_x, self.mag_scale_y, self.mag_scale_z, self.static_press_1_bias, self.static_press_1_scale, self.static_press_2_bias, self.static_press_2_scale, self.dpl_bay_press_bias, self.dpl_bay_press_scale), force_mavlink1=force_mavlink1)
+                return MAVLink_message.pack(self, mav, 210, struct.pack('<Qfffffffffffffffff', self.timestamp, self.gyro_bias_x, self.gyro_bias_y, self.gyro_bias_z, self.mag_bias_x, self.mag_bias_y, self.mag_bias_z, self.mag_scale_x, self.mag_scale_y, self.mag_scale_z, self.static_press_1_bias, self.static_press_1_scale, self.static_press_2_bias, self.static_press_2_scale, self.dpl_bay_press_bias, self.dpl_bay_press_scale, self.dynamic_press_bias, self.dynamic_press_scale), force_mavlink1=force_mavlink1)
 
 
 mavlink_map = {
@@ -5107,7 +5110,7 @@ class MAVLink(object):
 
         def rocket_flight_tm_encode(self, timestamp, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, mea_apogee, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, vn100_qx, vn100_qy, vn100_qz, vn100_qw, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, battery_voltage, cam_battery_voltage, temperature):
                 '''
-                High Rate Telemetry
+                High Rate Rocket Telemetry
 
                 timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
                 pressure_ada              : Atmospheric pressure estimated by ADA [Pa] (type:float)
@@ -5160,7 +5163,7 @@ class MAVLink(object):
 
         def rocket_flight_tm_send(self, timestamp, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, mea_apogee, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, vn100_qx, vn100_qy, vn100_qz, vn100_qw, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, battery_voltage, cam_battery_voltage, temperature, force_mavlink1=False):
                 '''
-                High Rate Telemetry
+                High Rate Rocket Telemetry
 
                 timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
                 pressure_ada              : Atmospheric pressure estimated by ADA [Pa] (type:float)
@@ -5211,13 +5214,14 @@ class MAVLink(object):
                 '''
                 return self.send(self.rocket_flight_tm_encode(timestamp, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, mea_apogee, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, vn100_qx, vn100_qy, vn100_qz, vn100_qw, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, battery_voltage, cam_battery_voltage, temperature), force_mavlink1=force_mavlink1)
 
-        def payload_flight_tm_encode(self, timestamp, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, battery_voltage, cam_battery_voltage, temperature):
+        def payload_flight_tm_encode(self, timestamp, pressure_digi, pressure_static, pressure_dynamic, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, battery_voltage, cam_battery_voltage, temperature):
                 '''
-                High Rate Telemetry
+                High Rate Payload Telemetry
 
                 timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
                 pressure_digi             : Pressure from digital sensor [Pa] (type:float)
                 pressure_static           : Pressure from static port [Pa] (type:float)
+                pressure_dynamic          : Pressure from dynamic port [Pa] (type:float)
                 airspeed_pitot            : Pitot airspeed [m/s] (type:float)
                 altitude_agl              : Altitude above ground level [m] (type:float)
                 acc_x                     : Acceleration on X axis (body) [m/s^2] (type:float)
@@ -5256,15 +5260,16 @@ class MAVLink(object):
                 temperature               : Temperature [degC] (type:float)
 
                 '''
-                return MAVLink_payload_flight_tm_message(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_fix, gps_lat, gps_lon, gps_alt, fmm_state, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, battery_voltage, cam_battery_voltage, temperature)
+                return MAVLink_payload_flight_tm_message(timestamp, pressure_digi, pressure_static, pressure_dynamic, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, battery_voltage, cam_battery_voltage, temperature)
 
-        def payload_flight_tm_send(self, timestamp, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, battery_voltage, cam_battery_voltage, temperature, force_mavlink1=False):
+        def payload_flight_tm_send(self, timestamp, pressure_digi, pressure_static, pressure_dynamic, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, battery_voltage, cam_battery_voltage, temperature, force_mavlink1=False):
                 '''
-                High Rate Telemetry
+                High Rate Payload Telemetry
 
                 timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
                 pressure_digi             : Pressure from digital sensor [Pa] (type:float)
                 pressure_static           : Pressure from static port [Pa] (type:float)
+                pressure_dynamic          : Pressure from dynamic port [Pa] (type:float)
                 airspeed_pitot            : Pitot airspeed [m/s] (type:float)
                 altitude_agl              : Altitude above ground level [m] (type:float)
                 acc_x                     : Acceleration on X axis (body) [m/s^2] (type:float)
@@ -5303,11 +5308,11 @@ class MAVLink(object):
                 temperature               : Temperature [degC] (type:float)
 
                 '''
-                return self.send(self.payload_flight_tm_encode(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_fix, gps_lat, gps_lon, gps_alt, fmm_state, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, battery_voltage, cam_battery_voltage, temperature), force_mavlink1=force_mavlink1)
+                return self.send(self.payload_flight_tm_encode(timestamp, pressure_digi, pressure_static, pressure_dynamic, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, fmm_state, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, battery_voltage, cam_battery_voltage, temperature), force_mavlink1=force_mavlink1)
 
         def rocket_stats_tm_encode(self, timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, shutdown_ts, shutdown_alt, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, dpl_bay_max_pressure_ts, dpl_bay_max_pressure, ref_lat, ref_lon, ref_alt, cpu_load, free_heap, ada_state, abk_state, nas_state, mea_state, exp_angle, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, hil_state):
                 '''
-                Low Rate Telemetry
+                Low Rate Rocket Telemetry
 
                 timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
                 liftoff_ts                : System clock at liftoff [us] (type:uint64_t)
@@ -5360,7 +5365,7 @@ class MAVLink(object):
 
         def rocket_stats_tm_send(self, timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, shutdown_ts, shutdown_alt, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, dpl_bay_max_pressure_ts, dpl_bay_max_pressure, ref_lat, ref_lon, ref_alt, cpu_load, free_heap, ada_state, abk_state, nas_state, mea_state, exp_angle, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, hil_state, force_mavlink1=False):
                 '''
-                Low Rate Telemetry
+                Low Rate Rocket Telemetry
 
                 timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
                 liftoff_ts                : System clock at liftoff [us] (type:uint64_t)
@@ -5411,10 +5416,11 @@ class MAVLink(object):
                 '''
                 return self.send(self.rocket_stats_tm_encode(timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, shutdown_ts, shutdown_alt, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, dpl_bay_max_pressure_ts, dpl_bay_max_pressure, ref_lat, ref_lon, ref_alt, cpu_load, free_heap, ada_state, abk_state, nas_state, mea_state, exp_angle, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, log_number, log_good, payload_board_state, motor_board_state, payload_can_status, motor_can_status, rig_can_status, hil_state), force_mavlink1=force_mavlink1)
 
-        def payload_stats_tm_encode(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_emc_n, wing_emc_e, wing_m1_n, wing_m1_e, wing_m2_n, wing_m2_e, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wes_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state):
+        def payload_stats_tm_encode(self, timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_target_lat, wing_target_lon, wing_active_target_n, wing_active_target_e, wing_algorithm, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wnc_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state):
                 '''
-                Low Rate Telemetry
+                Low Rate Payload Telemetry
 
+                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
                 liftoff_ts                : System clock at liftoff [us] (type:uint64_t)
                 liftoff_max_acc_ts        : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
                 liftoff_max_acc           : Maximum liftoff acceleration [m/s2] (type:float)
@@ -5429,12 +5435,11 @@ class MAVLink(object):
                 apogee_alt                : Apogee altitude [m] (type:float)
                 apogee_max_acc_ts         : System clock at max acceleration after apogee [us] (type:uint64_t)
                 apogee_max_acc            : Max acceleration after apogee [m/s2] (type:float)
-                wing_emc_n                : Wing controller EMC N [m] (type:float)
-                wing_emc_e                : Wing controller EMC E [m] (type:float)
-                wing_m1_n                 : Wing controller M1 N [m] (type:float)
-                wing_m1_e                 : Wing controller M1 E [m] (type:float)
-                wing_m2_n                 : Wing controller M2 N [m] (type:float)
-                wing_m2_e                 : Wing controller M2 E [m] (type:float)
+                wing_target_lat           : Wing target latitude [deg] (type:float)
+                wing_target_lon           : Wing target longitude [deg] (type:float)
+                wing_active_target_n        : Wing active target N [m] (type:float)
+                wing_active_target_e        : Wing active target E [m] (type:float)
+                wing_algorithm            : Wing selected algorithm (type:uint8_t)
                 dpl_ts                    : System clock at main deployment [us] (type:uint64_t)
                 dpl_alt                   : Deployment altitude [m] (type:float)
                 dpl_max_acc_ts            : System clock at max acceleration during main deployment [us] (type:uint64_t)
@@ -5446,7 +5451,7 @@ class MAVLink(object):
                 cpu_load                  : CPU load in percentage (type:float)
                 free_heap                 : Amount of available heap in memory (type:uint32_t)
                 nas_state                 : NAS FSM State (type:uint8_t)
-                wes_state                 : Wind Estimation System FSM State (type:uint8_t)
+                wnc_state                 : Wing Controller State (type:uint8_t)
                 pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
@@ -5460,12 +5465,13 @@ class MAVLink(object):
                 hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
 
                 '''
-                return MAVLink_payload_stats_tm_message(liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_emc_n, wing_emc_e, wing_m1_n, wing_m1_e, wing_m2_n, wing_m2_e, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wes_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state)
+                return MAVLink_payload_stats_tm_message(timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_target_lat, wing_target_lon, wing_active_target_n, wing_active_target_e, wing_algorithm, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wnc_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state)
 
-        def payload_stats_tm_send(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_emc_n, wing_emc_e, wing_m1_n, wing_m1_e, wing_m2_n, wing_m2_e, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wes_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state, force_mavlink1=False):
+        def payload_stats_tm_send(self, timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_target_lat, wing_target_lon, wing_active_target_n, wing_active_target_e, wing_algorithm, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wnc_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state, force_mavlink1=False):
                 '''
-                Low Rate Telemetry
+                Low Rate Payload Telemetry
 
+                timestamp                 : Timestamp in microseconds [us] (type:uint64_t)
                 liftoff_ts                : System clock at liftoff [us] (type:uint64_t)
                 liftoff_max_acc_ts        : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
                 liftoff_max_acc           : Maximum liftoff acceleration [m/s2] (type:float)
@@ -5480,12 +5486,11 @@ class MAVLink(object):
                 apogee_alt                : Apogee altitude [m] (type:float)
                 apogee_max_acc_ts         : System clock at max acceleration after apogee [us] (type:uint64_t)
                 apogee_max_acc            : Max acceleration after apogee [m/s2] (type:float)
-                wing_emc_n                : Wing controller EMC N [m] (type:float)
-                wing_emc_e                : Wing controller EMC E [m] (type:float)
-                wing_m1_n                 : Wing controller M1 N [m] (type:float)
-                wing_m1_e                 : Wing controller M1 E [m] (type:float)
-                wing_m2_n                 : Wing controller M2 N [m] (type:float)
-                wing_m2_e                 : Wing controller M2 E [m] (type:float)
+                wing_target_lat           : Wing target latitude [deg] (type:float)
+                wing_target_lon           : Wing target longitude [deg] (type:float)
+                wing_active_target_n        : Wing active target N [m] (type:float)
+                wing_active_target_e        : Wing active target E [m] (type:float)
+                wing_algorithm            : Wing selected algorithm (type:uint8_t)
                 dpl_ts                    : System clock at main deployment [us] (type:uint64_t)
                 dpl_alt                   : Deployment altitude [m] (type:float)
                 dpl_max_acc_ts            : System clock at max acceleration during main deployment [us] (type:uint64_t)
@@ -5497,7 +5502,7 @@ class MAVLink(object):
                 cpu_load                  : CPU load in percentage (type:float)
                 free_heap                 : Amount of available heap in memory (type:uint32_t)
                 nas_state                 : NAS FSM State (type:uint8_t)
-                wes_state                 : Wind Estimation System FSM State (type:uint8_t)
+                wnc_state                 : Wing Controller State (type:uint8_t)
                 pin_launch                : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 pin_nosecone              : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
                 cutter_presence           : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
@@ -5511,7 +5516,7 @@ class MAVLink(object):
                 hil_state                 : 1 if the board is currently in HIL mode (type:uint8_t)
 
                 '''
-                return self.send(self.payload_stats_tm_encode(liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_emc_n, wing_emc_e, wing_m1_n, wing_m1_e, wing_m2_n, wing_m2_e, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wes_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state), force_mavlink1=force_mavlink1)
+                return self.send(self.payload_stats_tm_encode(timestamp, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, max_speed_ts, max_speed, max_speed_altitude, max_mach_ts, max_mach, apogee_ts, apogee_lat, apogee_lon, apogee_alt, apogee_max_acc_ts, apogee_max_acc, wing_target_lat, wing_target_lon, wing_active_target_n, wing_active_target_e, wing_algorithm, dpl_ts, dpl_alt, dpl_max_acc_ts, dpl_max_acc, ref_lat, ref_lon, ref_alt, min_pressure, cpu_load, free_heap, nas_state, wnc_state, pin_launch, pin_nosecone, cutter_presence, log_number, log_good, main_board_state, motor_board_state, main_can_status, motor_can_status, rig_can_status, hil_state), force_mavlink1=force_mavlink1)
 
         def gse_tm_encode(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, nitrogen_valve_state, gmm_state, tars_state, arming_state, battery_voltage, current_consumption, umbilical_current_consumption, main_board_state, payload_board_state, motor_board_state, main_can_status, payload_can_status, motor_can_status, log_number, log_good):
                 '''
@@ -5615,7 +5620,7 @@ class MAVLink(object):
                 '''
                 return self.send(self.motor_tm_encode(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, log_number, log_good, hil_state), force_mavlink1=force_mavlink1)
 
-        def calibration_tm_encode(self, timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale):
+        def calibration_tm_encode(self, timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale, dynamic_press_bias, dynamic_press_scale):
                 '''
                 Calibration telemetry
 
@@ -5635,11 +5640,13 @@ class MAVLink(object):
                 static_press_2_scale        : Static pressure 2 scale (type:float)
                 dpl_bay_press_bias        : Deployment bay pressure bias [Pa] (type:float)
                 dpl_bay_press_scale        : Deployment bay pressure scale (type:float)
+                dynamic_press_bias        : Dynamic pressure bias [Pa] (type:float)
+                dynamic_press_scale        : Dynamic pressure scale (type:float)
 
                 '''
-                return MAVLink_calibration_tm_message(timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale)
+                return MAVLink_calibration_tm_message(timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale, dynamic_press_bias, dynamic_press_scale)
 
-        def calibration_tm_send(self, timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale, force_mavlink1=False):
+        def calibration_tm_send(self, timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale, dynamic_press_bias, dynamic_press_scale, force_mavlink1=False):
                 '''
                 Calibration telemetry
 
@@ -5659,7 +5666,9 @@ class MAVLink(object):
                 static_press_2_scale        : Static pressure 2 scale (type:float)
                 dpl_bay_press_bias        : Deployment bay pressure bias [Pa] (type:float)
                 dpl_bay_press_scale        : Deployment bay pressure scale (type:float)
+                dynamic_press_bias        : Dynamic pressure bias [Pa] (type:float)
+                dynamic_press_scale        : Dynamic pressure scale (type:float)
 
                 '''
-                return self.send(self.calibration_tm_encode(timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale), force_mavlink1=force_mavlink1)
+                return self.send(self.calibration_tm_encode(timestamp, gyro_bias_x, gyro_bias_y, gyro_bias_z, mag_bias_x, mag_bias_y, mag_bias_z, mag_scale_x, mag_scale_y, mag_scale_z, static_press_1_bias, static_press_1_scale, static_press_2_bias, static_press_2_scale, dpl_bay_press_bias, dpl_bay_press_scale, dynamic_press_bias, dynamic_press_scale), force_mavlink1=force_mavlink1)
 
diff --git a/mavlink_lib/lyra/lyra.h b/mavlink_lib/lyra/lyra.h
index 03a81d5821f91df7c0aed0b821a4ce22377b5c71..ad774b29ba0822a1f14191ab690ae45dd7daec12 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 -3518193324732693372
+#define MAVLINK_THIS_XML_HASH -6747370196428817221
 
 #ifdef __cplusplus
 extern "C" {
@@ -20,11 +20,11 @@ extern "C" {
 // MESSAGE LENGTHS AND CRCS
 
 #ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 16, 8, 2, 4, 8, 1, 4, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 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, 36, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 104, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 46, 28, 20, 44, 53, 77, 29, 178, 154, 180, 169, 56, 37, 68, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 16, 8, 2, 4, 8, 1, 4, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 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, 36, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 104, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 46, 28, 20, 44, 53, 77, 29, 178, 158, 180, 170, 56, 37, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #endif
 
 #ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 226, 160, 113, 38, 71, 168, 67, 218, 44, 81, 181, 199, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 110, 22, 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, 103, 9, 68, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 239, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 48, 142, 108, 39, 19, 234, 66, 11, 235, 138, 195, 206, 33, 67, 31, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 226, 160, 113, 38, 71, 168, 67, 218, 44, 81, 181, 199, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 110, 22, 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, 103, 9, 68, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 239, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 48, 142, 108, 39, 19, 234, 66, 11, 235, 188, 195, 99, 33, 67, 210, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #endif
 
 #include "../protocol.h"
@@ -272,7 +272,7 @@ typedef enum PinsList
 
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -3518193324732693372
+#define MAVLINK_THIS_XML_HASH -6747370196428817221
 
 #if MAVLINK_THIS_XML_HASH == MAVLINK_PRIMARY_XML_HASH
 # define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_QUAT_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_CALIBRATION_PRESSURE_TC, MAVLINK_MESSAGE_INFO_SET_INITIAL_MEA_MASS_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, MAVLINK_MESSAGE_INFO_SET_NITROGEN_TIME_TC, MAVLINK_MESSAGE_INFO_SET_COOLING_TIME_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_MULTIPLIER_TC, MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_ARP_COMMAND_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_WACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, MAVLINK_MESSAGE_INFO_REFERENCE_TM, MAVLINK_MESSAGE_INFO_REGISTRY_FLOAT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_INT_TM, MAVLINK_MESSAGE_INFO_REGISTRY_COORD_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ARP_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_CAN_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_MEA_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, MAVLINK_MESSAGE_INFO_CALIBRATION_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
diff --git a/mavlink_lib/lyra/mavlink.h b/mavlink_lib/lyra/mavlink.h
index 863dcf0be232d1fe79f4c25c0a00d8657add3f4c..58f93a843e87d8c4376e381361ab6fddc1e168d1 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 -3518193324732693372
+#define MAVLINK_PRIMARY_XML_HASH -6747370196428817221
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 254
diff --git a/mavlink_lib/lyra/mavlink_msg_calibration_tm.h b/mavlink_lib/lyra/mavlink_msg_calibration_tm.h
index 451a43094ab8f7ea0133f89d8ec059f0b1e4ddfe..b78cfdfde98ece3713e14ff0c5a9566f6b7d43a9 100644
--- a/mavlink_lib/lyra/mavlink_msg_calibration_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_calibration_tm.h
@@ -21,15 +21,17 @@ typedef struct __mavlink_calibration_tm_t {
  float static_press_2_scale; /*<  Static pressure 2 scale*/
  float dpl_bay_press_bias; /*< [Pa] Deployment bay pressure bias*/
  float dpl_bay_press_scale; /*<  Deployment bay pressure scale*/
+ float dynamic_press_bias; /*< [Pa] Dynamic pressure bias*/
+ float dynamic_press_scale; /*<  Dynamic pressure scale*/
 } mavlink_calibration_tm_t;
 
-#define MAVLINK_MSG_ID_CALIBRATION_TM_LEN 68
-#define MAVLINK_MSG_ID_CALIBRATION_TM_MIN_LEN 68
-#define MAVLINK_MSG_ID_214_LEN 68
-#define MAVLINK_MSG_ID_214_MIN_LEN 68
+#define MAVLINK_MSG_ID_CALIBRATION_TM_LEN 76
+#define MAVLINK_MSG_ID_CALIBRATION_TM_MIN_LEN 76
+#define MAVLINK_MSG_ID_214_LEN 76
+#define MAVLINK_MSG_ID_214_MIN_LEN 76
 
-#define MAVLINK_MSG_ID_CALIBRATION_TM_CRC 31
-#define MAVLINK_MSG_ID_214_CRC 31
+#define MAVLINK_MSG_ID_CALIBRATION_TM_CRC 210
+#define MAVLINK_MSG_ID_214_CRC 210
 
 
 
@@ -37,7 +39,7 @@ typedef struct __mavlink_calibration_tm_t {
 #define MAVLINK_MESSAGE_INFO_CALIBRATION_TM { \
     214, \
     "CALIBRATION_TM", \
-    16, \
+    18, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_calibration_tm_t, timestamp) }, \
          { "gyro_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_calibration_tm_t, gyro_bias_x) }, \
          { "gyro_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_calibration_tm_t, gyro_bias_y) }, \
@@ -54,12 +56,14 @@ typedef struct __mavlink_calibration_tm_t {
          { "static_press_2_scale", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_calibration_tm_t, static_press_2_scale) }, \
          { "dpl_bay_press_bias", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_calibration_tm_t, dpl_bay_press_bias) }, \
          { "dpl_bay_press_scale", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_calibration_tm_t, dpl_bay_press_scale) }, \
+         { "dynamic_press_bias", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_calibration_tm_t, dynamic_press_bias) }, \
+         { "dynamic_press_scale", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_calibration_tm_t, dynamic_press_scale) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_CALIBRATION_TM { \
     "CALIBRATION_TM", \
-    16, \
+    18, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_calibration_tm_t, timestamp) }, \
          { "gyro_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_calibration_tm_t, gyro_bias_x) }, \
          { "gyro_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_calibration_tm_t, gyro_bias_y) }, \
@@ -76,6 +80,8 @@ typedef struct __mavlink_calibration_tm_t {
          { "static_press_2_scale", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_calibration_tm_t, static_press_2_scale) }, \
          { "dpl_bay_press_bias", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_calibration_tm_t, dpl_bay_press_bias) }, \
          { "dpl_bay_press_scale", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_calibration_tm_t, dpl_bay_press_scale) }, \
+         { "dynamic_press_bias", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_calibration_tm_t, dynamic_press_bias) }, \
+         { "dynamic_press_scale", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_calibration_tm_t, dynamic_press_scale) }, \
          } \
 }
 #endif
@@ -102,10 +108,12 @@ typedef struct __mavlink_calibration_tm_t {
  * @param static_press_2_scale  Static pressure 2 scale
  * @param dpl_bay_press_bias [Pa] Deployment bay pressure bias
  * @param dpl_bay_press_scale  Deployment bay pressure scale
+ * @param dynamic_press_bias [Pa] Dynamic pressure bias
+ * @param dynamic_press_scale  Dynamic pressure scale
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_calibration_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, float gyro_bias_x, float gyro_bias_y, float gyro_bias_z, float mag_bias_x, float mag_bias_y, float mag_bias_z, float mag_scale_x, float mag_scale_y, float mag_scale_z, float static_press_1_bias, float static_press_1_scale, float static_press_2_bias, float static_press_2_scale, float dpl_bay_press_bias, float dpl_bay_press_scale)
+                               uint64_t timestamp, float gyro_bias_x, float gyro_bias_y, float gyro_bias_z, float mag_bias_x, float mag_bias_y, float mag_bias_z, float mag_scale_x, float mag_scale_y, float mag_scale_z, float static_press_1_bias, float static_press_1_scale, float static_press_2_bias, float static_press_2_scale, float dpl_bay_press_bias, float dpl_bay_press_scale, float dynamic_press_bias, float dynamic_press_scale)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_CALIBRATION_TM_LEN];
@@ -125,6 +133,8 @@ static inline uint16_t mavlink_msg_calibration_tm_pack(uint8_t system_id, uint8_
     _mav_put_float(buf, 56, static_press_2_scale);
     _mav_put_float(buf, 60, dpl_bay_press_bias);
     _mav_put_float(buf, 64, dpl_bay_press_scale);
+    _mav_put_float(buf, 68, dynamic_press_bias);
+    _mav_put_float(buf, 72, dynamic_press_scale);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CALIBRATION_TM_LEN);
 #else
@@ -145,6 +155,8 @@ static inline uint16_t mavlink_msg_calibration_tm_pack(uint8_t system_id, uint8_
     packet.static_press_2_scale = static_press_2_scale;
     packet.dpl_bay_press_bias = dpl_bay_press_bias;
     packet.dpl_bay_press_scale = dpl_bay_press_scale;
+    packet.dynamic_press_bias = dynamic_press_bias;
+    packet.dynamic_press_scale = dynamic_press_scale;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CALIBRATION_TM_LEN);
 #endif
@@ -175,11 +187,13 @@ static inline uint16_t mavlink_msg_calibration_tm_pack(uint8_t system_id, uint8_
  * @param static_press_2_scale  Static pressure 2 scale
  * @param dpl_bay_press_bias [Pa] Deployment bay pressure bias
  * @param dpl_bay_press_scale  Deployment bay pressure scale
+ * @param dynamic_press_bias [Pa] Dynamic pressure bias
+ * @param dynamic_press_scale  Dynamic pressure scale
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_calibration_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,float gyro_bias_x,float gyro_bias_y,float gyro_bias_z,float mag_bias_x,float mag_bias_y,float mag_bias_z,float mag_scale_x,float mag_scale_y,float mag_scale_z,float static_press_1_bias,float static_press_1_scale,float static_press_2_bias,float static_press_2_scale,float dpl_bay_press_bias,float dpl_bay_press_scale)
+                                   uint64_t timestamp,float gyro_bias_x,float gyro_bias_y,float gyro_bias_z,float mag_bias_x,float mag_bias_y,float mag_bias_z,float mag_scale_x,float mag_scale_y,float mag_scale_z,float static_press_1_bias,float static_press_1_scale,float static_press_2_bias,float static_press_2_scale,float dpl_bay_press_bias,float dpl_bay_press_scale,float dynamic_press_bias,float dynamic_press_scale)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_CALIBRATION_TM_LEN];
@@ -199,6 +213,8 @@ static inline uint16_t mavlink_msg_calibration_tm_pack_chan(uint8_t system_id, u
     _mav_put_float(buf, 56, static_press_2_scale);
     _mav_put_float(buf, 60, dpl_bay_press_bias);
     _mav_put_float(buf, 64, dpl_bay_press_scale);
+    _mav_put_float(buf, 68, dynamic_press_bias);
+    _mav_put_float(buf, 72, dynamic_press_scale);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CALIBRATION_TM_LEN);
 #else
@@ -219,6 +235,8 @@ static inline uint16_t mavlink_msg_calibration_tm_pack_chan(uint8_t system_id, u
     packet.static_press_2_scale = static_press_2_scale;
     packet.dpl_bay_press_bias = dpl_bay_press_bias;
     packet.dpl_bay_press_scale = dpl_bay_press_scale;
+    packet.dynamic_press_bias = dynamic_press_bias;
+    packet.dynamic_press_scale = dynamic_press_scale;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CALIBRATION_TM_LEN);
 #endif
@@ -237,7 +255,7 @@ static inline uint16_t mavlink_msg_calibration_tm_pack_chan(uint8_t system_id, u
  */
 static inline uint16_t mavlink_msg_calibration_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_calibration_tm_t* calibration_tm)
 {
-    return mavlink_msg_calibration_tm_pack(system_id, component_id, msg, calibration_tm->timestamp, calibration_tm->gyro_bias_x, calibration_tm->gyro_bias_y, calibration_tm->gyro_bias_z, calibration_tm->mag_bias_x, calibration_tm->mag_bias_y, calibration_tm->mag_bias_z, calibration_tm->mag_scale_x, calibration_tm->mag_scale_y, calibration_tm->mag_scale_z, calibration_tm->static_press_1_bias, calibration_tm->static_press_1_scale, calibration_tm->static_press_2_bias, calibration_tm->static_press_2_scale, calibration_tm->dpl_bay_press_bias, calibration_tm->dpl_bay_press_scale);
+    return mavlink_msg_calibration_tm_pack(system_id, component_id, msg, calibration_tm->timestamp, calibration_tm->gyro_bias_x, calibration_tm->gyro_bias_y, calibration_tm->gyro_bias_z, calibration_tm->mag_bias_x, calibration_tm->mag_bias_y, calibration_tm->mag_bias_z, calibration_tm->mag_scale_x, calibration_tm->mag_scale_y, calibration_tm->mag_scale_z, calibration_tm->static_press_1_bias, calibration_tm->static_press_1_scale, calibration_tm->static_press_2_bias, calibration_tm->static_press_2_scale, calibration_tm->dpl_bay_press_bias, calibration_tm->dpl_bay_press_scale, calibration_tm->dynamic_press_bias, calibration_tm->dynamic_press_scale);
 }
 
 /**
@@ -251,7 +269,7 @@ static inline uint16_t mavlink_msg_calibration_tm_encode(uint8_t system_id, uint
  */
 static inline uint16_t mavlink_msg_calibration_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_calibration_tm_t* calibration_tm)
 {
-    return mavlink_msg_calibration_tm_pack_chan(system_id, component_id, chan, msg, calibration_tm->timestamp, calibration_tm->gyro_bias_x, calibration_tm->gyro_bias_y, calibration_tm->gyro_bias_z, calibration_tm->mag_bias_x, calibration_tm->mag_bias_y, calibration_tm->mag_bias_z, calibration_tm->mag_scale_x, calibration_tm->mag_scale_y, calibration_tm->mag_scale_z, calibration_tm->static_press_1_bias, calibration_tm->static_press_1_scale, calibration_tm->static_press_2_bias, calibration_tm->static_press_2_scale, calibration_tm->dpl_bay_press_bias, calibration_tm->dpl_bay_press_scale);
+    return mavlink_msg_calibration_tm_pack_chan(system_id, component_id, chan, msg, calibration_tm->timestamp, calibration_tm->gyro_bias_x, calibration_tm->gyro_bias_y, calibration_tm->gyro_bias_z, calibration_tm->mag_bias_x, calibration_tm->mag_bias_y, calibration_tm->mag_bias_z, calibration_tm->mag_scale_x, calibration_tm->mag_scale_y, calibration_tm->mag_scale_z, calibration_tm->static_press_1_bias, calibration_tm->static_press_1_scale, calibration_tm->static_press_2_bias, calibration_tm->static_press_2_scale, calibration_tm->dpl_bay_press_bias, calibration_tm->dpl_bay_press_scale, calibration_tm->dynamic_press_bias, calibration_tm->dynamic_press_scale);
 }
 
 /**
@@ -274,10 +292,12 @@ static inline uint16_t mavlink_msg_calibration_tm_encode_chan(uint8_t system_id,
  * @param static_press_2_scale  Static pressure 2 scale
  * @param dpl_bay_press_bias [Pa] Deployment bay pressure bias
  * @param dpl_bay_press_scale  Deployment bay pressure scale
+ * @param dynamic_press_bias [Pa] Dynamic pressure bias
+ * @param dynamic_press_scale  Dynamic pressure scale
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_calibration_tm_send(mavlink_channel_t chan, uint64_t timestamp, float gyro_bias_x, float gyro_bias_y, float gyro_bias_z, float mag_bias_x, float mag_bias_y, float mag_bias_z, float mag_scale_x, float mag_scale_y, float mag_scale_z, float static_press_1_bias, float static_press_1_scale, float static_press_2_bias, float static_press_2_scale, float dpl_bay_press_bias, float dpl_bay_press_scale)
+static inline void mavlink_msg_calibration_tm_send(mavlink_channel_t chan, uint64_t timestamp, float gyro_bias_x, float gyro_bias_y, float gyro_bias_z, float mag_bias_x, float mag_bias_y, float mag_bias_z, float mag_scale_x, float mag_scale_y, float mag_scale_z, float static_press_1_bias, float static_press_1_scale, float static_press_2_bias, float static_press_2_scale, float dpl_bay_press_bias, float dpl_bay_press_scale, float dynamic_press_bias, float dynamic_press_scale)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_CALIBRATION_TM_LEN];
@@ -297,6 +317,8 @@ static inline void mavlink_msg_calibration_tm_send(mavlink_channel_t chan, uint6
     _mav_put_float(buf, 56, static_press_2_scale);
     _mav_put_float(buf, 60, dpl_bay_press_bias);
     _mav_put_float(buf, 64, dpl_bay_press_scale);
+    _mav_put_float(buf, 68, dynamic_press_bias);
+    _mav_put_float(buf, 72, dynamic_press_scale);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CALIBRATION_TM, buf, MAVLINK_MSG_ID_CALIBRATION_TM_MIN_LEN, MAVLINK_MSG_ID_CALIBRATION_TM_LEN, MAVLINK_MSG_ID_CALIBRATION_TM_CRC);
 #else
@@ -317,6 +339,8 @@ static inline void mavlink_msg_calibration_tm_send(mavlink_channel_t chan, uint6
     packet.static_press_2_scale = static_press_2_scale;
     packet.dpl_bay_press_bias = dpl_bay_press_bias;
     packet.dpl_bay_press_scale = dpl_bay_press_scale;
+    packet.dynamic_press_bias = dynamic_press_bias;
+    packet.dynamic_press_scale = dynamic_press_scale;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CALIBRATION_TM, (const char *)&packet, MAVLINK_MSG_ID_CALIBRATION_TM_MIN_LEN, MAVLINK_MSG_ID_CALIBRATION_TM_LEN, MAVLINK_MSG_ID_CALIBRATION_TM_CRC);
 #endif
@@ -330,7 +354,7 @@ static inline void mavlink_msg_calibration_tm_send(mavlink_channel_t chan, uint6
 static inline void mavlink_msg_calibration_tm_send_struct(mavlink_channel_t chan, const mavlink_calibration_tm_t* calibration_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_calibration_tm_send(chan, calibration_tm->timestamp, calibration_tm->gyro_bias_x, calibration_tm->gyro_bias_y, calibration_tm->gyro_bias_z, calibration_tm->mag_bias_x, calibration_tm->mag_bias_y, calibration_tm->mag_bias_z, calibration_tm->mag_scale_x, calibration_tm->mag_scale_y, calibration_tm->mag_scale_z, calibration_tm->static_press_1_bias, calibration_tm->static_press_1_scale, calibration_tm->static_press_2_bias, calibration_tm->static_press_2_scale, calibration_tm->dpl_bay_press_bias, calibration_tm->dpl_bay_press_scale);
+    mavlink_msg_calibration_tm_send(chan, calibration_tm->timestamp, calibration_tm->gyro_bias_x, calibration_tm->gyro_bias_y, calibration_tm->gyro_bias_z, calibration_tm->mag_bias_x, calibration_tm->mag_bias_y, calibration_tm->mag_bias_z, calibration_tm->mag_scale_x, calibration_tm->mag_scale_y, calibration_tm->mag_scale_z, calibration_tm->static_press_1_bias, calibration_tm->static_press_1_scale, calibration_tm->static_press_2_bias, calibration_tm->static_press_2_scale, calibration_tm->dpl_bay_press_bias, calibration_tm->dpl_bay_press_scale, calibration_tm->dynamic_press_bias, calibration_tm->dynamic_press_scale);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CALIBRATION_TM, (const char *)calibration_tm, MAVLINK_MSG_ID_CALIBRATION_TM_MIN_LEN, MAVLINK_MSG_ID_CALIBRATION_TM_LEN, MAVLINK_MSG_ID_CALIBRATION_TM_CRC);
 #endif
@@ -344,7 +368,7 @@ static inline void mavlink_msg_calibration_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_calibration_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float gyro_bias_x, float gyro_bias_y, float gyro_bias_z, float mag_bias_x, float mag_bias_y, float mag_bias_z, float mag_scale_x, float mag_scale_y, float mag_scale_z, float static_press_1_bias, float static_press_1_scale, float static_press_2_bias, float static_press_2_scale, float dpl_bay_press_bias, float dpl_bay_press_scale)
+static inline void mavlink_msg_calibration_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float gyro_bias_x, float gyro_bias_y, float gyro_bias_z, float mag_bias_x, float mag_bias_y, float mag_bias_z, float mag_scale_x, float mag_scale_y, float mag_scale_z, float static_press_1_bias, float static_press_1_scale, float static_press_2_bias, float static_press_2_scale, float dpl_bay_press_bias, float dpl_bay_press_scale, float dynamic_press_bias, float dynamic_press_scale)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -364,6 +388,8 @@ static inline void mavlink_msg_calibration_tm_send_buf(mavlink_message_t *msgbuf
     _mav_put_float(buf, 56, static_press_2_scale);
     _mav_put_float(buf, 60, dpl_bay_press_bias);
     _mav_put_float(buf, 64, dpl_bay_press_scale);
+    _mav_put_float(buf, 68, dynamic_press_bias);
+    _mav_put_float(buf, 72, dynamic_press_scale);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CALIBRATION_TM, buf, MAVLINK_MSG_ID_CALIBRATION_TM_MIN_LEN, MAVLINK_MSG_ID_CALIBRATION_TM_LEN, MAVLINK_MSG_ID_CALIBRATION_TM_CRC);
 #else
@@ -384,6 +410,8 @@ static inline void mavlink_msg_calibration_tm_send_buf(mavlink_message_t *msgbuf
     packet->static_press_2_scale = static_press_2_scale;
     packet->dpl_bay_press_bias = dpl_bay_press_bias;
     packet->dpl_bay_press_scale = dpl_bay_press_scale;
+    packet->dynamic_press_bias = dynamic_press_bias;
+    packet->dynamic_press_scale = dynamic_press_scale;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CALIBRATION_TM, (const char *)packet, MAVLINK_MSG_ID_CALIBRATION_TM_MIN_LEN, MAVLINK_MSG_ID_CALIBRATION_TM_LEN, MAVLINK_MSG_ID_CALIBRATION_TM_CRC);
 #endif
@@ -555,6 +583,26 @@ static inline float mavlink_msg_calibration_tm_get_dpl_bay_press_scale(const mav
     return _MAV_RETURN_float(msg,  64);
 }
 
+/**
+ * @brief Get field dynamic_press_bias from calibration_tm message
+ *
+ * @return [Pa] Dynamic pressure bias
+ */
+static inline float mavlink_msg_calibration_tm_get_dynamic_press_bias(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  68);
+}
+
+/**
+ * @brief Get field dynamic_press_scale from calibration_tm message
+ *
+ * @return  Dynamic pressure scale
+ */
+static inline float mavlink_msg_calibration_tm_get_dynamic_press_scale(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  72);
+}
+
 /**
  * @brief Decode a calibration_tm message into a struct
  *
@@ -580,6 +628,8 @@ static inline void mavlink_msg_calibration_tm_decode(const mavlink_message_t* ms
     calibration_tm->static_press_2_scale = mavlink_msg_calibration_tm_get_static_press_2_scale(msg);
     calibration_tm->dpl_bay_press_bias = mavlink_msg_calibration_tm_get_dpl_bay_press_bias(msg);
     calibration_tm->dpl_bay_press_scale = mavlink_msg_calibration_tm_get_dpl_bay_press_scale(msg);
+    calibration_tm->dynamic_press_bias = mavlink_msg_calibration_tm_get_dynamic_press_bias(msg);
+    calibration_tm->dynamic_press_scale = mavlink_msg_calibration_tm_get_dynamic_press_scale(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_CALIBRATION_TM_LEN? msg->len : MAVLINK_MSG_ID_CALIBRATION_TM_LEN;
         memset(calibration_tm, 0, MAVLINK_MSG_ID_CALIBRATION_TM_LEN);
diff --git a/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h b/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h
index 7d1f851413b4c3141c22d592a6c619be05f92b4d..34f88bb624bf8aa0e4aee02595be95d1ff7cc220 100644
--- a/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h
@@ -8,6 +8,7 @@ typedef struct __mavlink_payload_flight_tm_t {
  uint64_t timestamp; /*< [us] Timestamp in microseconds*/
  float pressure_digi; /*< [Pa] Pressure from digital sensor*/
  float pressure_static; /*< [Pa] Pressure from static port*/
+ float pressure_dynamic; /*< [Pa] Pressure from dynamic port*/
  float airspeed_pitot; /*< [m/s] Pitot airspeed*/
  float altitude_agl; /*< [m] Altitude above ground level*/
  float acc_x; /*< [m/s^2] Acceleration on X axis (body)*/
@@ -46,13 +47,13 @@ typedef struct __mavlink_payload_flight_tm_t {
  uint8_t fmm_state; /*<  Flight Mode Manager State*/
 } mavlink_payload_flight_tm_t;
 
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN 154
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN 154
-#define MAVLINK_MSG_ID_209_LEN 154
-#define MAVLINK_MSG_ID_209_MIN_LEN 154
+#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN 158
+#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN 158
+#define MAVLINK_MSG_ID_209_LEN 158
+#define MAVLINK_MSG_ID_209_MIN_LEN 158
 
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC 138
-#define MAVLINK_MSG_ID_209_CRC 138
+#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC 188
+#define MAVLINK_MSG_ID_209_CRC 188
 
 
 
@@ -60,91 +61,93 @@ typedef struct __mavlink_payload_flight_tm_t {
 #define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \
     209, \
     "PAYLOAD_FLIGHT_TM", \
-    39, \
+    40, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
          { "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) }, \
-         { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_payload_flight_tm_t, altitude_agl) }, \
-         { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_payload_flight_tm_t, acc_x) }, \
-         { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_payload_flight_tm_t, acc_y) }, \
-         { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_flight_tm_t, acc_z) }, \
-         { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_flight_tm_t, gyro_x) }, \
-         { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_flight_tm_t, gyro_y) }, \
-         { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_flight_tm_t, gyro_z) }, \
-         { "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, 152, 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) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 153, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
-         { "left_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_flight_tm_t, left_servo_angle) }, \
-         { "right_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_flight_tm_t, right_servo_angle) }, \
-         { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_flight_tm_t, nas_n) }, \
-         { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_flight_tm_t, nas_e) }, \
-         { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_flight_tm_t, nas_d) }, \
-         { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_flight_tm_t, nas_vn) }, \
-         { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_flight_tm_t, nas_ve) }, \
-         { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_flight_tm_t, nas_vd) }, \
-         { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_flight_tm_t, nas_qx) }, \
-         { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_flight_tm_t, nas_qy) }, \
-         { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_flight_tm_t, nas_qz) }, \
-         { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_flight_tm_t, nas_qw) }, \
-         { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_payload_flight_tm_t, nas_bias_x) }, \
-         { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_payload_flight_tm_t, nas_bias_y) }, \
-         { "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) }, \
-         { "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) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
+         { "pressure_dynamic", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, pressure_dynamic) }, \
+         { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \
+         { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_payload_flight_tm_t, altitude_agl) }, \
+         { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_payload_flight_tm_t, acc_x) }, \
+         { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_flight_tm_t, acc_y) }, \
+         { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_flight_tm_t, acc_z) }, \
+         { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_flight_tm_t, gyro_x) }, \
+         { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_flight_tm_t, gyro_y) }, \
+         { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_flight_tm_t, gyro_z) }, \
+         { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_flight_tm_t, mag_x) }, \
+         { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_flight_tm_t, mag_y) }, \
+         { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, mag_z) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
+         { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
+         { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
+         { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
+         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
+         { "left_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_flight_tm_t, left_servo_angle) }, \
+         { "right_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_flight_tm_t, right_servo_angle) }, \
+         { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_flight_tm_t, nas_n) }, \
+         { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_flight_tm_t, nas_e) }, \
+         { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_flight_tm_t, nas_d) }, \
+         { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_flight_tm_t, nas_vn) }, \
+         { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_flight_tm_t, nas_ve) }, \
+         { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_flight_tm_t, nas_vd) }, \
+         { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_flight_tm_t, nas_qx) }, \
+         { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_flight_tm_t, nas_qy) }, \
+         { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_flight_tm_t, nas_qz) }, \
+         { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_payload_flight_tm_t, nas_qw) }, \
+         { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_payload_flight_tm_t, nas_bias_x) }, \
+         { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_flight_tm_t, nas_bias_y) }, \
+         { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_flight_tm_t, nas_bias_z) }, \
+         { "wes_n", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_payload_flight_tm_t, wes_n) }, \
+         { "wes_e", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, wes_e) }, \
+         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, battery_voltage) }, \
+         { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, cam_battery_voltage) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \
     "PAYLOAD_FLIGHT_TM", \
-    39, \
+    40, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
          { "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) }, \
-         { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_payload_flight_tm_t, altitude_agl) }, \
-         { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_payload_flight_tm_t, acc_x) }, \
-         { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_payload_flight_tm_t, acc_y) }, \
-         { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_flight_tm_t, acc_z) }, \
-         { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_flight_tm_t, gyro_x) }, \
-         { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_flight_tm_t, gyro_y) }, \
-         { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_flight_tm_t, gyro_z) }, \
-         { "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, 152, 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) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 153, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
-         { "left_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_flight_tm_t, left_servo_angle) }, \
-         { "right_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_flight_tm_t, right_servo_angle) }, \
-         { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_flight_tm_t, nas_n) }, \
-         { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_flight_tm_t, nas_e) }, \
-         { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_flight_tm_t, nas_d) }, \
-         { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_flight_tm_t, nas_vn) }, \
-         { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_flight_tm_t, nas_ve) }, \
-         { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_flight_tm_t, nas_vd) }, \
-         { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_flight_tm_t, nas_qx) }, \
-         { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_flight_tm_t, nas_qy) }, \
-         { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_flight_tm_t, nas_qz) }, \
-         { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_flight_tm_t, nas_qw) }, \
-         { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_payload_flight_tm_t, nas_bias_x) }, \
-         { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_payload_flight_tm_t, nas_bias_y) }, \
-         { "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) }, \
-         { "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) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
+         { "pressure_dynamic", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, pressure_dynamic) }, \
+         { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \
+         { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_payload_flight_tm_t, altitude_agl) }, \
+         { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_payload_flight_tm_t, acc_x) }, \
+         { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_flight_tm_t, acc_y) }, \
+         { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_flight_tm_t, acc_z) }, \
+         { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_flight_tm_t, gyro_x) }, \
+         { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_flight_tm_t, gyro_y) }, \
+         { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_flight_tm_t, gyro_z) }, \
+         { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_flight_tm_t, mag_x) }, \
+         { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_flight_tm_t, mag_y) }, \
+         { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, mag_z) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
+         { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
+         { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
+         { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
+         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
+         { "left_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_flight_tm_t, left_servo_angle) }, \
+         { "right_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_flight_tm_t, right_servo_angle) }, \
+         { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_flight_tm_t, nas_n) }, \
+         { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_flight_tm_t, nas_e) }, \
+         { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_flight_tm_t, nas_d) }, \
+         { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_flight_tm_t, nas_vn) }, \
+         { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_flight_tm_t, nas_ve) }, \
+         { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_flight_tm_t, nas_vd) }, \
+         { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_flight_tm_t, nas_qx) }, \
+         { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_flight_tm_t, nas_qy) }, \
+         { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_flight_tm_t, nas_qz) }, \
+         { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_payload_flight_tm_t, nas_qw) }, \
+         { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_payload_flight_tm_t, nas_bias_x) }, \
+         { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_flight_tm_t, nas_bias_y) }, \
+         { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_flight_tm_t, nas_bias_z) }, \
+         { "wes_n", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_payload_flight_tm_t, wes_n) }, \
+         { "wes_e", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, wes_e) }, \
+         { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, battery_voltage) }, \
+         { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, cam_battery_voltage) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
          } \
 }
 #endif
@@ -158,6 +161,7 @@ typedef struct __mavlink_payload_flight_tm_t {
  * @param timestamp [us] Timestamp in microseconds
  * @param pressure_digi [Pa] Pressure from digital sensor
  * @param pressure_static [Pa] Pressure from static port
+ * @param pressure_dynamic [Pa] Pressure from dynamic port
  * @param airspeed_pitot [m/s] Pitot airspeed
  * @param altitude_agl [m] Altitude above ground level
  * @param acc_x [m/s^2] Acceleration on X axis (body)
@@ -197,49 +201,50 @@ typedef struct __mavlink_payload_flight_tm_t {
  * @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, 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, uint8_t fmm_state, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, float battery_voltage, float cam_battery_voltage, float temperature)
+                               uint64_t timestamp, float pressure_digi, float pressure_static, float pressure_dynamic, 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, uint8_t fmm_state, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, float 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];
     _mav_put_uint64_t(buf, 0, timestamp);
     _mav_put_float(buf, 8, pressure_digi);
     _mav_put_float(buf, 12, pressure_static);
-    _mav_put_float(buf, 16, airspeed_pitot);
-    _mav_put_float(buf, 20, altitude_agl);
-    _mav_put_float(buf, 24, acc_x);
-    _mav_put_float(buf, 28, acc_y);
-    _mav_put_float(buf, 32, acc_z);
-    _mav_put_float(buf, 36, gyro_x);
-    _mav_put_float(buf, 40, gyro_y);
-    _mav_put_float(buf, 44, gyro_z);
-    _mav_put_float(buf, 48, mag_x);
-    _mav_put_float(buf, 52, mag_y);
-    _mav_put_float(buf, 56, mag_z);
-    _mav_put_float(buf, 60, gps_lat);
-    _mav_put_float(buf, 64, gps_lon);
-    _mav_put_float(buf, 68, gps_alt);
-    _mav_put_float(buf, 72, left_servo_angle);
-    _mav_put_float(buf, 76, right_servo_angle);
-    _mav_put_float(buf, 80, nas_n);
-    _mav_put_float(buf, 84, nas_e);
-    _mav_put_float(buf, 88, nas_d);
-    _mav_put_float(buf, 92, nas_vn);
-    _mav_put_float(buf, 96, nas_ve);
-    _mav_put_float(buf, 100, nas_vd);
-    _mav_put_float(buf, 104, nas_qx);
-    _mav_put_float(buf, 108, nas_qy);
-    _mav_put_float(buf, 112, nas_qz);
-    _mav_put_float(buf, 116, nas_qw);
-    _mav_put_float(buf, 120, nas_bias_x);
-    _mav_put_float(buf, 124, nas_bias_y);
-    _mav_put_float(buf, 128, nas_bias_z);
-    _mav_put_float(buf, 132, wes_n);
-    _mav_put_float(buf, 136, wes_e);
-    _mav_put_float(buf, 140, battery_voltage);
-    _mav_put_float(buf, 144, cam_battery_voltage);
-    _mav_put_float(buf, 148, temperature);
-    _mav_put_uint8_t(buf, 152, gps_fix);
-    _mav_put_uint8_t(buf, 153, fmm_state);
+    _mav_put_float(buf, 16, pressure_dynamic);
+    _mav_put_float(buf, 20, airspeed_pitot);
+    _mav_put_float(buf, 24, altitude_agl);
+    _mav_put_float(buf, 28, acc_x);
+    _mav_put_float(buf, 32, acc_y);
+    _mav_put_float(buf, 36, acc_z);
+    _mav_put_float(buf, 40, gyro_x);
+    _mav_put_float(buf, 44, gyro_y);
+    _mav_put_float(buf, 48, gyro_z);
+    _mav_put_float(buf, 52, mag_x);
+    _mav_put_float(buf, 56, mag_y);
+    _mav_put_float(buf, 60, mag_z);
+    _mav_put_float(buf, 64, gps_lat);
+    _mav_put_float(buf, 68, gps_lon);
+    _mav_put_float(buf, 72, gps_alt);
+    _mav_put_float(buf, 76, left_servo_angle);
+    _mav_put_float(buf, 80, right_servo_angle);
+    _mav_put_float(buf, 84, nas_n);
+    _mav_put_float(buf, 88, nas_e);
+    _mav_put_float(buf, 92, nas_d);
+    _mav_put_float(buf, 96, nas_vn);
+    _mav_put_float(buf, 100, nas_ve);
+    _mav_put_float(buf, 104, nas_vd);
+    _mav_put_float(buf, 108, nas_qx);
+    _mav_put_float(buf, 112, nas_qy);
+    _mav_put_float(buf, 116, nas_qz);
+    _mav_put_float(buf, 120, nas_qw);
+    _mav_put_float(buf, 124, nas_bias_x);
+    _mav_put_float(buf, 128, nas_bias_y);
+    _mav_put_float(buf, 132, nas_bias_z);
+    _mav_put_float(buf, 136, wes_n);
+    _mav_put_float(buf, 140, wes_e);
+    _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, gps_fix);
+    _mav_put_uint8_t(buf, 157, fmm_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
 #else
@@ -247,6 +252,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
     packet.timestamp = timestamp;
     packet.pressure_digi = pressure_digi;
     packet.pressure_static = pressure_static;
+    packet.pressure_dynamic = pressure_dynamic;
     packet.airspeed_pitot = airspeed_pitot;
     packet.altitude_agl = altitude_agl;
     packet.acc_x = acc_x;
@@ -300,6 +306,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
  * @param timestamp [us] Timestamp in microseconds
  * @param pressure_digi [Pa] Pressure from digital sensor
  * @param pressure_static [Pa] Pressure from static port
+ * @param pressure_dynamic [Pa] Pressure from dynamic port
  * @param airspeed_pitot [m/s] Pitot airspeed
  * @param altitude_agl [m] Altitude above ground level
  * @param acc_x [m/s^2] Acceleration on X axis (body)
@@ -340,49 +347,50 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
  */
 static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,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,uint8_t fmm_state,float left_servo_angle,float right_servo_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float wes_n,float wes_e,float battery_voltage,float cam_battery_voltage,float temperature)
+                                   uint64_t timestamp,float pressure_digi,float pressure_static,float pressure_dynamic,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,uint8_t fmm_state,float left_servo_angle,float right_servo_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float wes_n,float wes_e,float 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];
     _mav_put_uint64_t(buf, 0, timestamp);
     _mav_put_float(buf, 8, pressure_digi);
     _mav_put_float(buf, 12, pressure_static);
-    _mav_put_float(buf, 16, airspeed_pitot);
-    _mav_put_float(buf, 20, altitude_agl);
-    _mav_put_float(buf, 24, acc_x);
-    _mav_put_float(buf, 28, acc_y);
-    _mav_put_float(buf, 32, acc_z);
-    _mav_put_float(buf, 36, gyro_x);
-    _mav_put_float(buf, 40, gyro_y);
-    _mav_put_float(buf, 44, gyro_z);
-    _mav_put_float(buf, 48, mag_x);
-    _mav_put_float(buf, 52, mag_y);
-    _mav_put_float(buf, 56, mag_z);
-    _mav_put_float(buf, 60, gps_lat);
-    _mav_put_float(buf, 64, gps_lon);
-    _mav_put_float(buf, 68, gps_alt);
-    _mav_put_float(buf, 72, left_servo_angle);
-    _mav_put_float(buf, 76, right_servo_angle);
-    _mav_put_float(buf, 80, nas_n);
-    _mav_put_float(buf, 84, nas_e);
-    _mav_put_float(buf, 88, nas_d);
-    _mav_put_float(buf, 92, nas_vn);
-    _mav_put_float(buf, 96, nas_ve);
-    _mav_put_float(buf, 100, nas_vd);
-    _mav_put_float(buf, 104, nas_qx);
-    _mav_put_float(buf, 108, nas_qy);
-    _mav_put_float(buf, 112, nas_qz);
-    _mav_put_float(buf, 116, nas_qw);
-    _mav_put_float(buf, 120, nas_bias_x);
-    _mav_put_float(buf, 124, nas_bias_y);
-    _mav_put_float(buf, 128, nas_bias_z);
-    _mav_put_float(buf, 132, wes_n);
-    _mav_put_float(buf, 136, wes_e);
-    _mav_put_float(buf, 140, battery_voltage);
-    _mav_put_float(buf, 144, cam_battery_voltage);
-    _mav_put_float(buf, 148, temperature);
-    _mav_put_uint8_t(buf, 152, gps_fix);
-    _mav_put_uint8_t(buf, 153, fmm_state);
+    _mav_put_float(buf, 16, pressure_dynamic);
+    _mav_put_float(buf, 20, airspeed_pitot);
+    _mav_put_float(buf, 24, altitude_agl);
+    _mav_put_float(buf, 28, acc_x);
+    _mav_put_float(buf, 32, acc_y);
+    _mav_put_float(buf, 36, acc_z);
+    _mav_put_float(buf, 40, gyro_x);
+    _mav_put_float(buf, 44, gyro_y);
+    _mav_put_float(buf, 48, gyro_z);
+    _mav_put_float(buf, 52, mag_x);
+    _mav_put_float(buf, 56, mag_y);
+    _mav_put_float(buf, 60, mag_z);
+    _mav_put_float(buf, 64, gps_lat);
+    _mav_put_float(buf, 68, gps_lon);
+    _mav_put_float(buf, 72, gps_alt);
+    _mav_put_float(buf, 76, left_servo_angle);
+    _mav_put_float(buf, 80, right_servo_angle);
+    _mav_put_float(buf, 84, nas_n);
+    _mav_put_float(buf, 88, nas_e);
+    _mav_put_float(buf, 92, nas_d);
+    _mav_put_float(buf, 96, nas_vn);
+    _mav_put_float(buf, 100, nas_ve);
+    _mav_put_float(buf, 104, nas_vd);
+    _mav_put_float(buf, 108, nas_qx);
+    _mav_put_float(buf, 112, nas_qy);
+    _mav_put_float(buf, 116, nas_qz);
+    _mav_put_float(buf, 120, nas_qw);
+    _mav_put_float(buf, 124, nas_bias_x);
+    _mav_put_float(buf, 128, nas_bias_y);
+    _mav_put_float(buf, 132, nas_bias_z);
+    _mav_put_float(buf, 136, wes_n);
+    _mav_put_float(buf, 140, wes_e);
+    _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, gps_fix);
+    _mav_put_uint8_t(buf, 157, fmm_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
 #else
@@ -390,6 +398,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id
     packet.timestamp = timestamp;
     packet.pressure_digi = pressure_digi;
     packet.pressure_static = pressure_static;
+    packet.pressure_dynamic = pressure_dynamic;
     packet.airspeed_pitot = airspeed_pitot;
     packet.altitude_agl = altitude_agl;
     packet.acc_x = acc_x;
@@ -444,7 +453,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->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->fmm_state, 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->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->temperature);
+    return mavlink_msg_payload_flight_tm_pack(system_id, component_id, msg, payload_flight_tm->timestamp, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->pressure_dynamic, 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->fmm_state, 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->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->temperature);
 }
 
 /**
@@ -458,7 +467,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->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->fmm_state, 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->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->temperature);
+    return mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, chan, msg, payload_flight_tm->timestamp, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->pressure_dynamic, 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->fmm_state, 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->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->temperature);
 }
 
 /**
@@ -468,6 +477,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_
  * @param timestamp [us] Timestamp in microseconds
  * @param pressure_digi [Pa] Pressure from digital sensor
  * @param pressure_static [Pa] Pressure from static port
+ * @param pressure_dynamic [Pa] Pressure from dynamic port
  * @param airspeed_pitot [m/s] Pitot airspeed
  * @param altitude_agl [m] Altitude above ground level
  * @param acc_x [m/s^2] Acceleration on X axis (body)
@@ -507,49 +517,50 @@ static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, 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, uint8_t fmm_state, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, float battery_voltage, float cam_battery_voltage, float temperature)
+static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, float pressure_digi, float pressure_static, float pressure_dynamic, 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, uint8_t fmm_state, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, float 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];
     _mav_put_uint64_t(buf, 0, timestamp);
     _mav_put_float(buf, 8, pressure_digi);
     _mav_put_float(buf, 12, pressure_static);
-    _mav_put_float(buf, 16, airspeed_pitot);
-    _mav_put_float(buf, 20, altitude_agl);
-    _mav_put_float(buf, 24, acc_x);
-    _mav_put_float(buf, 28, acc_y);
-    _mav_put_float(buf, 32, acc_z);
-    _mav_put_float(buf, 36, gyro_x);
-    _mav_put_float(buf, 40, gyro_y);
-    _mav_put_float(buf, 44, gyro_z);
-    _mav_put_float(buf, 48, mag_x);
-    _mav_put_float(buf, 52, mag_y);
-    _mav_put_float(buf, 56, mag_z);
-    _mav_put_float(buf, 60, gps_lat);
-    _mav_put_float(buf, 64, gps_lon);
-    _mav_put_float(buf, 68, gps_alt);
-    _mav_put_float(buf, 72, left_servo_angle);
-    _mav_put_float(buf, 76, right_servo_angle);
-    _mav_put_float(buf, 80, nas_n);
-    _mav_put_float(buf, 84, nas_e);
-    _mav_put_float(buf, 88, nas_d);
-    _mav_put_float(buf, 92, nas_vn);
-    _mav_put_float(buf, 96, nas_ve);
-    _mav_put_float(buf, 100, nas_vd);
-    _mav_put_float(buf, 104, nas_qx);
-    _mav_put_float(buf, 108, nas_qy);
-    _mav_put_float(buf, 112, nas_qz);
-    _mav_put_float(buf, 116, nas_qw);
-    _mav_put_float(buf, 120, nas_bias_x);
-    _mav_put_float(buf, 124, nas_bias_y);
-    _mav_put_float(buf, 128, nas_bias_z);
-    _mav_put_float(buf, 132, wes_n);
-    _mav_put_float(buf, 136, wes_e);
-    _mav_put_float(buf, 140, battery_voltage);
-    _mav_put_float(buf, 144, cam_battery_voltage);
-    _mav_put_float(buf, 148, temperature);
-    _mav_put_uint8_t(buf, 152, gps_fix);
-    _mav_put_uint8_t(buf, 153, fmm_state);
+    _mav_put_float(buf, 16, pressure_dynamic);
+    _mav_put_float(buf, 20, airspeed_pitot);
+    _mav_put_float(buf, 24, altitude_agl);
+    _mav_put_float(buf, 28, acc_x);
+    _mav_put_float(buf, 32, acc_y);
+    _mav_put_float(buf, 36, acc_z);
+    _mav_put_float(buf, 40, gyro_x);
+    _mav_put_float(buf, 44, gyro_y);
+    _mav_put_float(buf, 48, gyro_z);
+    _mav_put_float(buf, 52, mag_x);
+    _mav_put_float(buf, 56, mag_y);
+    _mav_put_float(buf, 60, mag_z);
+    _mav_put_float(buf, 64, gps_lat);
+    _mav_put_float(buf, 68, gps_lon);
+    _mav_put_float(buf, 72, gps_alt);
+    _mav_put_float(buf, 76, left_servo_angle);
+    _mav_put_float(buf, 80, right_servo_angle);
+    _mav_put_float(buf, 84, nas_n);
+    _mav_put_float(buf, 88, nas_e);
+    _mav_put_float(buf, 92, nas_d);
+    _mav_put_float(buf, 96, nas_vn);
+    _mav_put_float(buf, 100, nas_ve);
+    _mav_put_float(buf, 104, nas_vd);
+    _mav_put_float(buf, 108, nas_qx);
+    _mav_put_float(buf, 112, nas_qy);
+    _mav_put_float(buf, 116, nas_qz);
+    _mav_put_float(buf, 120, nas_qw);
+    _mav_put_float(buf, 124, nas_bias_x);
+    _mav_put_float(buf, 128, nas_bias_y);
+    _mav_put_float(buf, 132, nas_bias_z);
+    _mav_put_float(buf, 136, wes_n);
+    _mav_put_float(buf, 140, wes_e);
+    _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, gps_fix);
+    _mav_put_uint8_t(buf, 157, fmm_state);
 
     _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
@@ -557,6 +568,7 @@ static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, ui
     packet.timestamp = timestamp;
     packet.pressure_digi = pressure_digi;
     packet.pressure_static = pressure_static;
+    packet.pressure_dynamic = pressure_dynamic;
     packet.airspeed_pitot = airspeed_pitot;
     packet.altitude_agl = altitude_agl;
     packet.acc_x = acc_x;
@@ -606,7 +618,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->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->fmm_state, 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->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->temperature);
+    mavlink_msg_payload_flight_tm_send(chan, payload_flight_tm->timestamp, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->pressure_dynamic, 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->fmm_state, 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->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
@@ -620,49 +632,50 @@ 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, 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, uint8_t fmm_state, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, float battery_voltage, float cam_battery_voltage, float temperature)
+static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float pressure_digi, float pressure_static, float pressure_dynamic, 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, uint8_t fmm_state, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, float battery_voltage, float cam_battery_voltage, float temperature)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
     _mav_put_uint64_t(buf, 0, timestamp);
     _mav_put_float(buf, 8, pressure_digi);
     _mav_put_float(buf, 12, pressure_static);
-    _mav_put_float(buf, 16, airspeed_pitot);
-    _mav_put_float(buf, 20, altitude_agl);
-    _mav_put_float(buf, 24, acc_x);
-    _mav_put_float(buf, 28, acc_y);
-    _mav_put_float(buf, 32, acc_z);
-    _mav_put_float(buf, 36, gyro_x);
-    _mav_put_float(buf, 40, gyro_y);
-    _mav_put_float(buf, 44, gyro_z);
-    _mav_put_float(buf, 48, mag_x);
-    _mav_put_float(buf, 52, mag_y);
-    _mav_put_float(buf, 56, mag_z);
-    _mav_put_float(buf, 60, gps_lat);
-    _mav_put_float(buf, 64, gps_lon);
-    _mav_put_float(buf, 68, gps_alt);
-    _mav_put_float(buf, 72, left_servo_angle);
-    _mav_put_float(buf, 76, right_servo_angle);
-    _mav_put_float(buf, 80, nas_n);
-    _mav_put_float(buf, 84, nas_e);
-    _mav_put_float(buf, 88, nas_d);
-    _mav_put_float(buf, 92, nas_vn);
-    _mav_put_float(buf, 96, nas_ve);
-    _mav_put_float(buf, 100, nas_vd);
-    _mav_put_float(buf, 104, nas_qx);
-    _mav_put_float(buf, 108, nas_qy);
-    _mav_put_float(buf, 112, nas_qz);
-    _mav_put_float(buf, 116, nas_qw);
-    _mav_put_float(buf, 120, nas_bias_x);
-    _mav_put_float(buf, 124, nas_bias_y);
-    _mav_put_float(buf, 128, nas_bias_z);
-    _mav_put_float(buf, 132, wes_n);
-    _mav_put_float(buf, 136, wes_e);
-    _mav_put_float(buf, 140, battery_voltage);
-    _mav_put_float(buf, 144, cam_battery_voltage);
-    _mav_put_float(buf, 148, temperature);
-    _mav_put_uint8_t(buf, 152, gps_fix);
-    _mav_put_uint8_t(buf, 153, fmm_state);
+    _mav_put_float(buf, 16, pressure_dynamic);
+    _mav_put_float(buf, 20, airspeed_pitot);
+    _mav_put_float(buf, 24, altitude_agl);
+    _mav_put_float(buf, 28, acc_x);
+    _mav_put_float(buf, 32, acc_y);
+    _mav_put_float(buf, 36, acc_z);
+    _mav_put_float(buf, 40, gyro_x);
+    _mav_put_float(buf, 44, gyro_y);
+    _mav_put_float(buf, 48, gyro_z);
+    _mav_put_float(buf, 52, mag_x);
+    _mav_put_float(buf, 56, mag_y);
+    _mav_put_float(buf, 60, mag_z);
+    _mav_put_float(buf, 64, gps_lat);
+    _mav_put_float(buf, 68, gps_lon);
+    _mav_put_float(buf, 72, gps_alt);
+    _mav_put_float(buf, 76, left_servo_angle);
+    _mav_put_float(buf, 80, right_servo_angle);
+    _mav_put_float(buf, 84, nas_n);
+    _mav_put_float(buf, 88, nas_e);
+    _mav_put_float(buf, 92, nas_d);
+    _mav_put_float(buf, 96, nas_vn);
+    _mav_put_float(buf, 100, nas_ve);
+    _mav_put_float(buf, 104, nas_vd);
+    _mav_put_float(buf, 108, nas_qx);
+    _mav_put_float(buf, 112, nas_qy);
+    _mav_put_float(buf, 116, nas_qz);
+    _mav_put_float(buf, 120, nas_qw);
+    _mav_put_float(buf, 124, nas_bias_x);
+    _mav_put_float(buf, 128, nas_bias_y);
+    _mav_put_float(buf, 132, nas_bias_z);
+    _mav_put_float(buf, 136, wes_n);
+    _mav_put_float(buf, 140, wes_e);
+    _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, gps_fix);
+    _mav_put_uint8_t(buf, 157, fmm_state);
 
     _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
@@ -670,6 +683,7 @@ static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msg
     packet->timestamp = timestamp;
     packet->pressure_digi = pressure_digi;
     packet->pressure_static = pressure_static;
+    packet->pressure_dynamic = pressure_dynamic;
     packet->airspeed_pitot = airspeed_pitot;
     packet->altitude_agl = altitude_agl;
     packet->acc_x = acc_x;
@@ -747,6 +761,16 @@ static inline float mavlink_msg_payload_flight_tm_get_pressure_static(const mavl
     return _MAV_RETURN_float(msg,  12);
 }
 
+/**
+ * @brief Get field pressure_dynamic from payload_flight_tm message
+ *
+ * @return [Pa] Pressure from dynamic port
+ */
+static inline float mavlink_msg_payload_flight_tm_get_pressure_dynamic(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  16);
+}
+
 /**
  * @brief Get field airspeed_pitot from payload_flight_tm message
  *
@@ -754,7 +778,7 @@ static inline float mavlink_msg_payload_flight_tm_get_pressure_static(const mavl
  */
 static inline float mavlink_msg_payload_flight_tm_get_airspeed_pitot(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  16);
+    return _MAV_RETURN_float(msg,  20);
 }
 
 /**
@@ -764,7 +788,7 @@ static inline float mavlink_msg_payload_flight_tm_get_airspeed_pitot(const mavli
  */
 static inline float mavlink_msg_payload_flight_tm_get_altitude_agl(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  20);
+    return _MAV_RETURN_float(msg,  24);
 }
 
 /**
@@ -774,7 +798,7 @@ static inline float mavlink_msg_payload_flight_tm_get_altitude_agl(const mavlink
  */
 static inline float mavlink_msg_payload_flight_tm_get_acc_x(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  24);
+    return _MAV_RETURN_float(msg,  28);
 }
 
 /**
@@ -784,7 +808,7 @@ static inline float mavlink_msg_payload_flight_tm_get_acc_x(const mavlink_messag
  */
 static inline float mavlink_msg_payload_flight_tm_get_acc_y(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  28);
+    return _MAV_RETURN_float(msg,  32);
 }
 
 /**
@@ -794,7 +818,7 @@ static inline float mavlink_msg_payload_flight_tm_get_acc_y(const mavlink_messag
  */
 static inline float mavlink_msg_payload_flight_tm_get_acc_z(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  32);
+    return _MAV_RETURN_float(msg,  36);
 }
 
 /**
@@ -804,7 +828,7 @@ static inline float mavlink_msg_payload_flight_tm_get_acc_z(const mavlink_messag
  */
 static inline float mavlink_msg_payload_flight_tm_get_gyro_x(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  36);
+    return _MAV_RETURN_float(msg,  40);
 }
 
 /**
@@ -814,7 +838,7 @@ static inline float mavlink_msg_payload_flight_tm_get_gyro_x(const mavlink_messa
  */
 static inline float mavlink_msg_payload_flight_tm_get_gyro_y(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  40);
+    return _MAV_RETURN_float(msg,  44);
 }
 
 /**
@@ -824,7 +848,7 @@ static inline float mavlink_msg_payload_flight_tm_get_gyro_y(const mavlink_messa
  */
 static inline float mavlink_msg_payload_flight_tm_get_gyro_z(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  44);
+    return _MAV_RETURN_float(msg,  48);
 }
 
 /**
@@ -834,7 +858,7 @@ static inline float mavlink_msg_payload_flight_tm_get_gyro_z(const mavlink_messa
  */
 static inline float mavlink_msg_payload_flight_tm_get_mag_x(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  48);
+    return _MAV_RETURN_float(msg,  52);
 }
 
 /**
@@ -844,7 +868,7 @@ static inline float mavlink_msg_payload_flight_tm_get_mag_x(const mavlink_messag
  */
 static inline float mavlink_msg_payload_flight_tm_get_mag_y(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  52);
+    return _MAV_RETURN_float(msg,  56);
 }
 
 /**
@@ -854,7 +878,7 @@ static inline float mavlink_msg_payload_flight_tm_get_mag_y(const mavlink_messag
  */
 static inline float mavlink_msg_payload_flight_tm_get_mag_z(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  56);
+    return _MAV_RETURN_float(msg,  60);
 }
 
 /**
@@ -864,7 +888,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,  152);
+    return _MAV_RETURN_uint8_t(msg,  156);
 }
 
 /**
@@ -874,7 +898,7 @@ static inline uint8_t mavlink_msg_payload_flight_tm_get_gps_fix(const mavlink_me
  */
 static inline float mavlink_msg_payload_flight_tm_get_gps_lat(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  60);
+    return _MAV_RETURN_float(msg,  64);
 }
 
 /**
@@ -884,7 +908,7 @@ static inline float mavlink_msg_payload_flight_tm_get_gps_lat(const mavlink_mess
  */
 static inline float mavlink_msg_payload_flight_tm_get_gps_lon(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  64);
+    return _MAV_RETURN_float(msg,  68);
 }
 
 /**
@@ -894,7 +918,7 @@ static inline float mavlink_msg_payload_flight_tm_get_gps_lon(const mavlink_mess
  */
 static inline float mavlink_msg_payload_flight_tm_get_gps_alt(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  68);
+    return _MAV_RETURN_float(msg,  72);
 }
 
 /**
@@ -904,7 +928,7 @@ static inline float mavlink_msg_payload_flight_tm_get_gps_alt(const mavlink_mess
  */
 static inline uint8_t mavlink_msg_payload_flight_tm_get_fmm_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  153);
+    return _MAV_RETURN_uint8_t(msg,  157);
 }
 
 /**
@@ -914,7 +938,7 @@ static inline uint8_t mavlink_msg_payload_flight_tm_get_fmm_state(const mavlink_
  */
 static inline float mavlink_msg_payload_flight_tm_get_left_servo_angle(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  72);
+    return _MAV_RETURN_float(msg,  76);
 }
 
 /**
@@ -924,7 +948,7 @@ static inline float mavlink_msg_payload_flight_tm_get_left_servo_angle(const mav
  */
 static inline float mavlink_msg_payload_flight_tm_get_right_servo_angle(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  76);
+    return _MAV_RETURN_float(msg,  80);
 }
 
 /**
@@ -934,7 +958,7 @@ static inline float mavlink_msg_payload_flight_tm_get_right_servo_angle(const ma
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_n(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  80);
+    return _MAV_RETURN_float(msg,  84);
 }
 
 /**
@@ -944,7 +968,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_n(const mavlink_messag
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_e(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  84);
+    return _MAV_RETURN_float(msg,  88);
 }
 
 /**
@@ -954,7 +978,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_e(const mavlink_messag
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_d(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  88);
+    return _MAV_RETURN_float(msg,  92);
 }
 
 /**
@@ -964,7 +988,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_d(const mavlink_messag
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_vn(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  92);
+    return _MAV_RETURN_float(msg,  96);
 }
 
 /**
@@ -974,7 +998,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_vn(const mavlink_messa
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_ve(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  96);
+    return _MAV_RETURN_float(msg,  100);
 }
 
 /**
@@ -984,7 +1008,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_ve(const mavlink_messa
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_vd(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  100);
+    return _MAV_RETURN_float(msg,  104);
 }
 
 /**
@@ -994,7 +1018,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_vd(const mavlink_messa
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_qx(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  104);
+    return _MAV_RETURN_float(msg,  108);
 }
 
 /**
@@ -1004,7 +1028,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_qx(const mavlink_messa
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_qy(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  108);
+    return _MAV_RETURN_float(msg,  112);
 }
 
 /**
@@ -1014,7 +1038,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_qy(const mavlink_messa
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_qz(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  112);
+    return _MAV_RETURN_float(msg,  116);
 }
 
 /**
@@ -1024,7 +1048,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_qz(const mavlink_messa
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_qw(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  116);
+    return _MAV_RETURN_float(msg,  120);
 }
 
 /**
@@ -1034,7 +1058,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_qw(const mavlink_messa
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_bias_x(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  120);
+    return _MAV_RETURN_float(msg,  124);
 }
 
 /**
@@ -1044,7 +1068,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_bias_x(const mavlink_m
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_bias_y(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  124);
+    return _MAV_RETURN_float(msg,  128);
 }
 
 /**
@@ -1054,7 +1078,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_bias_y(const mavlink_m
  */
 static inline float mavlink_msg_payload_flight_tm_get_nas_bias_z(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  128);
+    return _MAV_RETURN_float(msg,  132);
 }
 
 /**
@@ -1064,7 +1088,7 @@ static inline float mavlink_msg_payload_flight_tm_get_nas_bias_z(const mavlink_m
  */
 static inline float mavlink_msg_payload_flight_tm_get_wes_n(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  132);
+    return _MAV_RETURN_float(msg,  136);
 }
 
 /**
@@ -1074,7 +1098,7 @@ static inline float mavlink_msg_payload_flight_tm_get_wes_n(const mavlink_messag
  */
 static inline float mavlink_msg_payload_flight_tm_get_wes_e(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  136);
+    return _MAV_RETURN_float(msg,  140);
 }
 
 /**
@@ -1084,7 +1108,7 @@ static inline float mavlink_msg_payload_flight_tm_get_wes_e(const mavlink_messag
  */
 static inline float mavlink_msg_payload_flight_tm_get_battery_voltage(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  140);
+    return _MAV_RETURN_float(msg,  144);
 }
 
 /**
@@ -1094,7 +1118,7 @@ static inline float mavlink_msg_payload_flight_tm_get_battery_voltage(const mavl
  */
 static inline float mavlink_msg_payload_flight_tm_get_cam_battery_voltage(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  144);
+    return _MAV_RETURN_float(msg,  148);
 }
 
 /**
@@ -1104,7 +1128,7 @@ static inline float mavlink_msg_payload_flight_tm_get_cam_battery_voltage(const
  */
 static inline float mavlink_msg_payload_flight_tm_get_temperature(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  148);
+    return _MAV_RETURN_float(msg,  152);
 }
 
 /**
@@ -1119,6 +1143,7 @@ static inline void mavlink_msg_payload_flight_tm_decode(const mavlink_message_t*
     payload_flight_tm->timestamp = mavlink_msg_payload_flight_tm_get_timestamp(msg);
     payload_flight_tm->pressure_digi = mavlink_msg_payload_flight_tm_get_pressure_digi(msg);
     payload_flight_tm->pressure_static = mavlink_msg_payload_flight_tm_get_pressure_static(msg);
+    payload_flight_tm->pressure_dynamic = mavlink_msg_payload_flight_tm_get_pressure_dynamic(msg);
     payload_flight_tm->airspeed_pitot = mavlink_msg_payload_flight_tm_get_airspeed_pitot(msg);
     payload_flight_tm->altitude_agl = mavlink_msg_payload_flight_tm_get_altitude_agl(msg);
     payload_flight_tm->acc_x = mavlink_msg_payload_flight_tm_get_acc_x(msg);
diff --git a/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h
index a7d04ef658f8237e9af249ad2ea1ba3782addc0d..becea83e0541d181c273cd9d4b5f34a79cc9bdc2 100644
--- a/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h
+++ b/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h
@@ -5,6 +5,7 @@
 
 
 typedef struct __mavlink_payload_stats_tm_t {
+ uint64_t timestamp; /*< [us] Timestamp in microseconds*/
  uint64_t liftoff_ts; /*< [us] System clock at liftoff*/
  uint64_t liftoff_max_acc_ts; /*< [us] System clock at the maximum liftoff acceleration*/
  uint64_t max_speed_ts; /*< [us] System clock at max speed*/
@@ -21,12 +22,10 @@ typedef struct __mavlink_payload_stats_tm_t {
  float apogee_lon; /*< [deg] Apogee longitude*/
  float apogee_alt; /*< [m] Apogee altitude*/
  float apogee_max_acc; /*< [m/s2] Max acceleration after apogee*/
- float wing_emc_n; /*< [m] Wing controller EMC N*/
- float wing_emc_e; /*< [m] Wing controller EMC E*/
- float wing_m1_n; /*< [m] Wing controller M1 N*/
- float wing_m1_e; /*< [m] Wing controller M1 E*/
- float wing_m2_n; /*< [m] Wing controller M2 N*/
- float wing_m2_e; /*< [m] Wing controller M2 E*/
+ float wing_target_lat; /*< [deg] Wing target latitude*/
+ float wing_target_lon; /*< [deg] Wing target longitude*/
+ float wing_active_target_n; /*< [m] Wing active target N*/
+ float wing_active_target_e; /*< [m] Wing active target E*/
  float dpl_alt; /*< [m] Deployment altitude*/
  float dpl_max_acc; /*< [m/s2] Max acceleration during main deployment*/
  float ref_lat; /*< [deg] Reference altitude*/
@@ -37,8 +36,9 @@ typedef struct __mavlink_payload_stats_tm_t {
  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 wing_algorithm; /*<  Wing selected algorithm*/
  uint8_t nas_state; /*<  NAS FSM State*/
- uint8_t wes_state; /*<  Wind Estimation System FSM State*/
+ uint8_t wnc_state; /*<  Wing Controller State*/
  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)*/
@@ -50,13 +50,13 @@ typedef struct __mavlink_payload_stats_tm_t {
  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 169
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN 169
-#define MAVLINK_MSG_ID_211_LEN 169
-#define MAVLINK_MSG_ID_211_MIN_LEN 169
+#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN 170
+#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN 170
+#define MAVLINK_MSG_ID_211_LEN 170
+#define MAVLINK_MSG_ID_211_MIN_LEN 170
 
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC 206
-#define MAVLINK_MSG_ID_211_CRC 206
+#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC 99
+#define MAVLINK_MSG_ID_211_CRC 99
 
 
 
@@ -65,29 +65,29 @@ typedef struct __mavlink_payload_stats_tm_t {
     211, \
     "PAYLOAD_STATS_TM", \
     43, \
-    {  { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_stats_tm_t, liftoff_ts) }, \
-         { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc_ts) }, \
-         { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc) }, \
-         { "max_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_payload_stats_tm_t, max_speed_ts) }, \
-         { "max_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_stats_tm_t, max_speed) }, \
-         { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_stats_tm_t, max_speed_altitude) }, \
-         { "max_mach_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_payload_stats_tm_t, max_mach_ts) }, \
-         { "max_mach", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_stats_tm_t, max_mach) }, \
-         { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 32, offsetof(mavlink_payload_stats_tm_t, apogee_ts) }, \
-         { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_stats_tm_t, apogee_lat) }, \
-         { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_stats_tm_t, apogee_lon) }, \
-         { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_stats_tm_t, apogee_alt) }, \
-         { "apogee_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 40, offsetof(mavlink_payload_stats_tm_t, apogee_max_acc_ts) }, \
-         { "apogee_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_stats_tm_t, apogee_max_acc) }, \
-         { "wing_emc_n", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_stats_tm_t, wing_emc_n) }, \
-         { "wing_emc_e", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_stats_tm_t, wing_emc_e) }, \
-         { "wing_m1_n", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_stats_tm_t, wing_m1_n) }, \
-         { "wing_m1_e", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_stats_tm_t, wing_m1_e) }, \
-         { "wing_m2_n", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_stats_tm_t, wing_m2_n) }, \
-         { "wing_m2_e", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_stats_tm_t, wing_m2_e) }, \
-         { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 48, offsetof(mavlink_payload_stats_tm_t, dpl_ts) }, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_stats_tm_t, timestamp) }, \
+         { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_payload_stats_tm_t, liftoff_ts) }, \
+         { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc_ts) }, \
+         { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc) }, \
+         { "max_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_payload_stats_tm_t, max_speed_ts) }, \
+         { "max_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_stats_tm_t, max_speed) }, \
+         { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_stats_tm_t, max_speed_altitude) }, \
+         { "max_mach_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 32, offsetof(mavlink_payload_stats_tm_t, max_mach_ts) }, \
+         { "max_mach", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_stats_tm_t, max_mach) }, \
+         { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 40, offsetof(mavlink_payload_stats_tm_t, apogee_ts) }, \
+         { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_stats_tm_t, apogee_lat) }, \
+         { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_stats_tm_t, apogee_lon) }, \
+         { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_stats_tm_t, apogee_alt) }, \
+         { "apogee_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 48, offsetof(mavlink_payload_stats_tm_t, apogee_max_acc_ts) }, \
+         { "apogee_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_stats_tm_t, apogee_max_acc) }, \
+         { "wing_target_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_stats_tm_t, wing_target_lat) }, \
+         { "wing_target_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_stats_tm_t, wing_target_lon) }, \
+         { "wing_active_target_n", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_stats_tm_t, wing_active_target_n) }, \
+         { "wing_active_target_e", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_stats_tm_t, wing_active_target_e) }, \
+         { "wing_algorithm", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_stats_tm_t, wing_algorithm) }, \
+         { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 56, offsetof(mavlink_payload_stats_tm_t, dpl_ts) }, \
          { "dpl_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_payload_stats_tm_t, dpl_alt) }, \
-         { "dpl_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 56, offsetof(mavlink_payload_stats_tm_t, dpl_max_acc_ts) }, \
+         { "dpl_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 64, offsetof(mavlink_payload_stats_tm_t, dpl_max_acc_ts) }, \
          { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_payload_stats_tm_t, dpl_max_acc) }, \
          { "ref_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_stats_tm_t, ref_lat) }, \
          { "ref_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_stats_tm_t, ref_lon) }, \
@@ -95,48 +95,48 @@ typedef struct __mavlink_payload_stats_tm_t {
          { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_stats_tm_t, min_pressure) }, \
          { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_stats_tm_t, cpu_load) }, \
          { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 148, offsetof(mavlink_payload_stats_tm_t, free_heap) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_stats_tm_t, nas_state) }, \
-         { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_payload_stats_tm_t, wes_state) }, \
-         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_stats_tm_t, pin_launch) }, \
-         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_stats_tm_t, pin_nosecone) }, \
-         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_payload_stats_tm_t, cutter_presence) }, \
+         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_payload_stats_tm_t, nas_state) }, \
+         { "wnc_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_stats_tm_t, wnc_state) }, \
+         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_stats_tm_t, pin_launch) }, \
+         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_payload_stats_tm_t, pin_nosecone) }, \
+         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_payload_stats_tm_t, cutter_presence) }, \
          { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 156, offsetof(mavlink_payload_stats_tm_t, log_number) }, \
          { "log_good", NULL, MAVLINK_TYPE_INT32_T, 0, 152, offsetof(mavlink_payload_stats_tm_t, log_good) }, \
-         { "main_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_payload_stats_tm_t, main_board_state) }, \
-         { "motor_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_payload_stats_tm_t, motor_board_state) }, \
-         { "main_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_payload_stats_tm_t, main_can_status) }, \
-         { "motor_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_payload_stats_tm_t, motor_can_status) }, \
-         { "rig_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_payload_stats_tm_t, rig_can_status) }, \
-         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_payload_stats_tm_t, hil_state) }, \
+         { "main_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_payload_stats_tm_t, main_board_state) }, \
+         { "motor_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_payload_stats_tm_t, motor_board_state) }, \
+         { "main_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_payload_stats_tm_t, main_can_status) }, \
+         { "motor_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_payload_stats_tm_t, motor_can_status) }, \
+         { "rig_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_payload_stats_tm_t, rig_can_status) }, \
+         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_payload_stats_tm_t, hil_state) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM { \
     "PAYLOAD_STATS_TM", \
     43, \
-    {  { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_stats_tm_t, liftoff_ts) }, \
-         { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc_ts) }, \
-         { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc) }, \
-         { "max_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_payload_stats_tm_t, max_speed_ts) }, \
-         { "max_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_stats_tm_t, max_speed) }, \
-         { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_stats_tm_t, max_speed_altitude) }, \
-         { "max_mach_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_payload_stats_tm_t, max_mach_ts) }, \
-         { "max_mach", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_stats_tm_t, max_mach) }, \
-         { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 32, offsetof(mavlink_payload_stats_tm_t, apogee_ts) }, \
-         { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_stats_tm_t, apogee_lat) }, \
-         { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_stats_tm_t, apogee_lon) }, \
-         { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_stats_tm_t, apogee_alt) }, \
-         { "apogee_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 40, offsetof(mavlink_payload_stats_tm_t, apogee_max_acc_ts) }, \
-         { "apogee_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_stats_tm_t, apogee_max_acc) }, \
-         { "wing_emc_n", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_stats_tm_t, wing_emc_n) }, \
-         { "wing_emc_e", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_stats_tm_t, wing_emc_e) }, \
-         { "wing_m1_n", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_stats_tm_t, wing_m1_n) }, \
-         { "wing_m1_e", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_stats_tm_t, wing_m1_e) }, \
-         { "wing_m2_n", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_stats_tm_t, wing_m2_n) }, \
-         { "wing_m2_e", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_stats_tm_t, wing_m2_e) }, \
-         { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 48, offsetof(mavlink_payload_stats_tm_t, dpl_ts) }, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_stats_tm_t, timestamp) }, \
+         { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_payload_stats_tm_t, liftoff_ts) }, \
+         { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc_ts) }, \
+         { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc) }, \
+         { "max_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_payload_stats_tm_t, max_speed_ts) }, \
+         { "max_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_stats_tm_t, max_speed) }, \
+         { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_stats_tm_t, max_speed_altitude) }, \
+         { "max_mach_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 32, offsetof(mavlink_payload_stats_tm_t, max_mach_ts) }, \
+         { "max_mach", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_stats_tm_t, max_mach) }, \
+         { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 40, offsetof(mavlink_payload_stats_tm_t, apogee_ts) }, \
+         { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_stats_tm_t, apogee_lat) }, \
+         { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_stats_tm_t, apogee_lon) }, \
+         { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_stats_tm_t, apogee_alt) }, \
+         { "apogee_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 48, offsetof(mavlink_payload_stats_tm_t, apogee_max_acc_ts) }, \
+         { "apogee_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_stats_tm_t, apogee_max_acc) }, \
+         { "wing_target_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_stats_tm_t, wing_target_lat) }, \
+         { "wing_target_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_stats_tm_t, wing_target_lon) }, \
+         { "wing_active_target_n", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_stats_tm_t, wing_active_target_n) }, \
+         { "wing_active_target_e", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_stats_tm_t, wing_active_target_e) }, \
+         { "wing_algorithm", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_stats_tm_t, wing_algorithm) }, \
+         { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 56, offsetof(mavlink_payload_stats_tm_t, dpl_ts) }, \
          { "dpl_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_payload_stats_tm_t, dpl_alt) }, \
-         { "dpl_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 56, offsetof(mavlink_payload_stats_tm_t, dpl_max_acc_ts) }, \
+         { "dpl_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 64, offsetof(mavlink_payload_stats_tm_t, dpl_max_acc_ts) }, \
          { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_payload_stats_tm_t, dpl_max_acc) }, \
          { "ref_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_stats_tm_t, ref_lat) }, \
          { "ref_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_stats_tm_t, ref_lon) }, \
@@ -144,19 +144,19 @@ typedef struct __mavlink_payload_stats_tm_t {
          { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_stats_tm_t, min_pressure) }, \
          { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_stats_tm_t, cpu_load) }, \
          { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 148, offsetof(mavlink_payload_stats_tm_t, free_heap) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_stats_tm_t, nas_state) }, \
-         { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_payload_stats_tm_t, wes_state) }, \
-         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_stats_tm_t, pin_launch) }, \
-         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_stats_tm_t, pin_nosecone) }, \
-         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_payload_stats_tm_t, cutter_presence) }, \
+         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_payload_stats_tm_t, nas_state) }, \
+         { "wnc_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_stats_tm_t, wnc_state) }, \
+         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_stats_tm_t, pin_launch) }, \
+         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_payload_stats_tm_t, pin_nosecone) }, \
+         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_payload_stats_tm_t, cutter_presence) }, \
          { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 156, offsetof(mavlink_payload_stats_tm_t, log_number) }, \
          { "log_good", NULL, MAVLINK_TYPE_INT32_T, 0, 152, offsetof(mavlink_payload_stats_tm_t, log_good) }, \
-         { "main_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_payload_stats_tm_t, main_board_state) }, \
-         { "motor_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_payload_stats_tm_t, motor_board_state) }, \
-         { "main_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_payload_stats_tm_t, main_can_status) }, \
-         { "motor_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_payload_stats_tm_t, motor_can_status) }, \
-         { "rig_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_payload_stats_tm_t, rig_can_status) }, \
-         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_payload_stats_tm_t, hil_state) }, \
+         { "main_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_payload_stats_tm_t, main_board_state) }, \
+         { "motor_board_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_payload_stats_tm_t, motor_board_state) }, \
+         { "main_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_payload_stats_tm_t, main_can_status) }, \
+         { "motor_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_payload_stats_tm_t, motor_can_status) }, \
+         { "rig_can_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_payload_stats_tm_t, rig_can_status) }, \
+         { "hil_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_payload_stats_tm_t, hil_state) }, \
          } \
 }
 #endif
@@ -167,6 +167,7 @@ typedef struct __mavlink_payload_stats_tm_t {
  * @param component_id ID of this component (e.g. 200 for IMU)
  * @param msg The MAVLink message to compress the data into
  *
+ * @param timestamp [us] Timestamp in microseconds
  * @param liftoff_ts [us] System clock at liftoff
  * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
  * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
@@ -181,12 +182,11 @@ typedef struct __mavlink_payload_stats_tm_t {
  * @param apogee_alt [m] Apogee altitude
  * @param apogee_max_acc_ts [us] System clock at max acceleration after apogee
  * @param apogee_max_acc [m/s2] Max acceleration after apogee
- * @param wing_emc_n [m] Wing controller EMC N
- * @param wing_emc_e [m] Wing controller EMC E
- * @param wing_m1_n [m] Wing controller M1 N
- * @param wing_m1_e [m] Wing controller M1 E
- * @param wing_m2_n [m] Wing controller M2 N
- * @param wing_m2_e [m] Wing controller M2 E
+ * @param wing_target_lat [deg] Wing target latitude
+ * @param wing_target_lon [deg] Wing target longitude
+ * @param wing_active_target_n [m] Wing active target N
+ * @param wing_active_target_e [m] Wing active target E
+ * @param wing_algorithm  Wing selected algorithm
  * @param dpl_ts [us] System clock at main deployment
  * @param dpl_alt [m] Deployment altitude
  * @param dpl_max_acc_ts [us] System clock at max acceleration during main deployment
@@ -198,7 +198,7 @@ typedef struct __mavlink_payload_stats_tm_t {
  * @param cpu_load  CPU load in percentage
  * @param free_heap  Amount of available heap in memory
  * @param nas_state  NAS FSM State
- * @param wes_state  Wind Estimation System FSM State
+ * @param wnc_state  Wing Controller State
  * @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)
@@ -213,32 +213,31 @@ typedef struct __mavlink_payload_stats_tm_t {
  * @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_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t max_speed_ts, float max_speed, float max_speed_altitude, uint64_t max_mach_ts, float max_mach, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, uint64_t apogee_max_acc_ts, float apogee_max_acc, float wing_emc_n, float wing_emc_e, float wing_m1_n, float wing_m1_e, float wing_m2_n, float wing_m2_e, uint64_t dpl_ts, float dpl_alt, uint64_t dpl_max_acc_ts, float dpl_max_acc, float ref_lat, float ref_lon, float ref_alt, float min_pressure, float cpu_load, uint32_t free_heap, uint8_t nas_state, uint8_t wes_state, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t cutter_presence, 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)
+                               uint64_t timestamp, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t max_speed_ts, float max_speed, float max_speed_altitude, uint64_t max_mach_ts, float max_mach, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, uint64_t apogee_max_acc_ts, float apogee_max_acc, float wing_target_lat, float wing_target_lon, float wing_active_target_n, float wing_active_target_e, uint8_t wing_algorithm, uint64_t dpl_ts, float dpl_alt, uint64_t dpl_max_acc_ts, float dpl_max_acc, float ref_lat, float ref_lon, float ref_alt, float min_pressure, float cpu_load, uint32_t free_heap, uint8_t nas_state, uint8_t wnc_state, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t cutter_presence, 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];
-    _mav_put_uint64_t(buf, 0, liftoff_ts);
-    _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
-    _mav_put_uint64_t(buf, 16, max_speed_ts);
-    _mav_put_uint64_t(buf, 24, max_mach_ts);
-    _mav_put_uint64_t(buf, 32, apogee_ts);
-    _mav_put_uint64_t(buf, 40, apogee_max_acc_ts);
-    _mav_put_uint64_t(buf, 48, dpl_ts);
-    _mav_put_uint64_t(buf, 56, dpl_max_acc_ts);
-    _mav_put_float(buf, 64, liftoff_max_acc);
-    _mav_put_float(buf, 68, max_speed);
-    _mav_put_float(buf, 72, max_speed_altitude);
-    _mav_put_float(buf, 76, max_mach);
-    _mav_put_float(buf, 80, apogee_lat);
-    _mav_put_float(buf, 84, apogee_lon);
-    _mav_put_float(buf, 88, apogee_alt);
-    _mav_put_float(buf, 92, apogee_max_acc);
-    _mav_put_float(buf, 96, wing_emc_n);
-    _mav_put_float(buf, 100, wing_emc_e);
-    _mav_put_float(buf, 104, wing_m1_n);
-    _mav_put_float(buf, 108, wing_m1_e);
-    _mav_put_float(buf, 112, wing_m2_n);
-    _mav_put_float(buf, 116, wing_m2_e);
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint64_t(buf, 8, liftoff_ts);
+    _mav_put_uint64_t(buf, 16, liftoff_max_acc_ts);
+    _mav_put_uint64_t(buf, 24, max_speed_ts);
+    _mav_put_uint64_t(buf, 32, max_mach_ts);
+    _mav_put_uint64_t(buf, 40, apogee_ts);
+    _mav_put_uint64_t(buf, 48, apogee_max_acc_ts);
+    _mav_put_uint64_t(buf, 56, dpl_ts);
+    _mav_put_uint64_t(buf, 64, dpl_max_acc_ts);
+    _mav_put_float(buf, 72, liftoff_max_acc);
+    _mav_put_float(buf, 76, max_speed);
+    _mav_put_float(buf, 80, max_speed_altitude);
+    _mav_put_float(buf, 84, max_mach);
+    _mav_put_float(buf, 88, apogee_lat);
+    _mav_put_float(buf, 92, apogee_lon);
+    _mav_put_float(buf, 96, apogee_alt);
+    _mav_put_float(buf, 100, apogee_max_acc);
+    _mav_put_float(buf, 104, wing_target_lat);
+    _mav_put_float(buf, 108, wing_target_lon);
+    _mav_put_float(buf, 112, wing_active_target_n);
+    _mav_put_float(buf, 116, wing_active_target_e);
     _mav_put_float(buf, 120, dpl_alt);
     _mav_put_float(buf, 124, dpl_max_acc);
     _mav_put_float(buf, 128, ref_lat);
@@ -249,21 +248,23 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint
     _mav_put_uint32_t(buf, 148, free_heap);
     _mav_put_int32_t(buf, 152, log_good);
     _mav_put_int16_t(buf, 156, log_number);
-    _mav_put_uint8_t(buf, 158, nas_state);
-    _mav_put_uint8_t(buf, 159, wes_state);
-    _mav_put_uint8_t(buf, 160, pin_launch);
-    _mav_put_uint8_t(buf, 161, pin_nosecone);
-    _mav_put_uint8_t(buf, 162, cutter_presence);
-    _mav_put_uint8_t(buf, 163, main_board_state);
-    _mav_put_uint8_t(buf, 164, motor_board_state);
-    _mav_put_uint8_t(buf, 165, main_can_status);
-    _mav_put_uint8_t(buf, 166, motor_can_status);
-    _mav_put_uint8_t(buf, 167, rig_can_status);
-    _mav_put_uint8_t(buf, 168, hil_state);
+    _mav_put_uint8_t(buf, 158, wing_algorithm);
+    _mav_put_uint8_t(buf, 159, nas_state);
+    _mav_put_uint8_t(buf, 160, wnc_state);
+    _mav_put_uint8_t(buf, 161, pin_launch);
+    _mav_put_uint8_t(buf, 162, pin_nosecone);
+    _mav_put_uint8_t(buf, 163, cutter_presence);
+    _mav_put_uint8_t(buf, 164, main_board_state);
+    _mav_put_uint8_t(buf, 165, motor_board_state);
+    _mav_put_uint8_t(buf, 166, main_can_status);
+    _mav_put_uint8_t(buf, 167, motor_can_status);
+    _mav_put_uint8_t(buf, 168, rig_can_status);
+    _mav_put_uint8_t(buf, 169, hil_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
 #else
     mavlink_payload_stats_tm_t packet;
+    packet.timestamp = timestamp;
     packet.liftoff_ts = liftoff_ts;
     packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
     packet.max_speed_ts = max_speed_ts;
@@ -280,12 +281,10 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint
     packet.apogee_lon = apogee_lon;
     packet.apogee_alt = apogee_alt;
     packet.apogee_max_acc = apogee_max_acc;
-    packet.wing_emc_n = wing_emc_n;
-    packet.wing_emc_e = wing_emc_e;
-    packet.wing_m1_n = wing_m1_n;
-    packet.wing_m1_e = wing_m1_e;
-    packet.wing_m2_n = wing_m2_n;
-    packet.wing_m2_e = wing_m2_e;
+    packet.wing_target_lat = wing_target_lat;
+    packet.wing_target_lon = wing_target_lon;
+    packet.wing_active_target_n = wing_active_target_n;
+    packet.wing_active_target_e = wing_active_target_e;
     packet.dpl_alt = dpl_alt;
     packet.dpl_max_acc = dpl_max_acc;
     packet.ref_lat = ref_lat;
@@ -296,8 +295,9 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint
     packet.free_heap = free_heap;
     packet.log_good = log_good;
     packet.log_number = log_number;
+    packet.wing_algorithm = wing_algorithm;
     packet.nas_state = nas_state;
-    packet.wes_state = wes_state;
+    packet.wnc_state = wnc_state;
     packet.pin_launch = pin_launch;
     packet.pin_nosecone = pin_nosecone;
     packet.cutter_presence = cutter_presence;
@@ -321,6 +321,7 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint
  * @param component_id ID of this component (e.g. 200 for IMU)
  * @param chan The MAVLink channel this message will be sent over
  * @param msg The MAVLink message to compress the data into
+ * @param timestamp [us] Timestamp in microseconds
  * @param liftoff_ts [us] System clock at liftoff
  * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
  * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
@@ -335,12 +336,11 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint
  * @param apogee_alt [m] Apogee altitude
  * @param apogee_max_acc_ts [us] System clock at max acceleration after apogee
  * @param apogee_max_acc [m/s2] Max acceleration after apogee
- * @param wing_emc_n [m] Wing controller EMC N
- * @param wing_emc_e [m] Wing controller EMC E
- * @param wing_m1_n [m] Wing controller M1 N
- * @param wing_m1_e [m] Wing controller M1 E
- * @param wing_m2_n [m] Wing controller M2 N
- * @param wing_m2_e [m] Wing controller M2 E
+ * @param wing_target_lat [deg] Wing target latitude
+ * @param wing_target_lon [deg] Wing target longitude
+ * @param wing_active_target_n [m] Wing active target N
+ * @param wing_active_target_e [m] Wing active target E
+ * @param wing_algorithm  Wing selected algorithm
  * @param dpl_ts [us] System clock at main deployment
  * @param dpl_alt [m] Deployment altitude
  * @param dpl_max_acc_ts [us] System clock at max acceleration during main deployment
@@ -352,7 +352,7 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint
  * @param cpu_load  CPU load in percentage
  * @param free_heap  Amount of available heap in memory
  * @param nas_state  NAS FSM State
- * @param wes_state  Wind Estimation System FSM State
+ * @param wnc_state  Wing Controller State
  * @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)
@@ -368,32 +368,31 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint
  */
 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_ts,uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t max_speed_ts,float max_speed,float max_speed_altitude,uint64_t max_mach_ts,float max_mach,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float apogee_alt,uint64_t apogee_max_acc_ts,float apogee_max_acc,float wing_emc_n,float wing_emc_e,float wing_m1_n,float wing_m1_e,float wing_m2_n,float wing_m2_e,uint64_t dpl_ts,float dpl_alt,uint64_t dpl_max_acc_ts,float dpl_max_acc,float ref_lat,float ref_lon,float ref_alt,float min_pressure,float cpu_load,uint32_t free_heap,uint8_t nas_state,uint8_t wes_state,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t cutter_presence,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)
+                                   uint64_t timestamp,uint64_t liftoff_ts,uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t max_speed_ts,float max_speed,float max_speed_altitude,uint64_t max_mach_ts,float max_mach,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float apogee_alt,uint64_t apogee_max_acc_ts,float apogee_max_acc,float wing_target_lat,float wing_target_lon,float wing_active_target_n,float wing_active_target_e,uint8_t wing_algorithm,uint64_t dpl_ts,float dpl_alt,uint64_t dpl_max_acc_ts,float dpl_max_acc,float ref_lat,float ref_lon,float ref_alt,float min_pressure,float cpu_load,uint32_t free_heap,uint8_t nas_state,uint8_t wnc_state,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t cutter_presence,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];
-    _mav_put_uint64_t(buf, 0, liftoff_ts);
-    _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
-    _mav_put_uint64_t(buf, 16, max_speed_ts);
-    _mav_put_uint64_t(buf, 24, max_mach_ts);
-    _mav_put_uint64_t(buf, 32, apogee_ts);
-    _mav_put_uint64_t(buf, 40, apogee_max_acc_ts);
-    _mav_put_uint64_t(buf, 48, dpl_ts);
-    _mav_put_uint64_t(buf, 56, dpl_max_acc_ts);
-    _mav_put_float(buf, 64, liftoff_max_acc);
-    _mav_put_float(buf, 68, max_speed);
-    _mav_put_float(buf, 72, max_speed_altitude);
-    _mav_put_float(buf, 76, max_mach);
-    _mav_put_float(buf, 80, apogee_lat);
-    _mav_put_float(buf, 84, apogee_lon);
-    _mav_put_float(buf, 88, apogee_alt);
-    _mav_put_float(buf, 92, apogee_max_acc);
-    _mav_put_float(buf, 96, wing_emc_n);
-    _mav_put_float(buf, 100, wing_emc_e);
-    _mav_put_float(buf, 104, wing_m1_n);
-    _mav_put_float(buf, 108, wing_m1_e);
-    _mav_put_float(buf, 112, wing_m2_n);
-    _mav_put_float(buf, 116, wing_m2_e);
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint64_t(buf, 8, liftoff_ts);
+    _mav_put_uint64_t(buf, 16, liftoff_max_acc_ts);
+    _mav_put_uint64_t(buf, 24, max_speed_ts);
+    _mav_put_uint64_t(buf, 32, max_mach_ts);
+    _mav_put_uint64_t(buf, 40, apogee_ts);
+    _mav_put_uint64_t(buf, 48, apogee_max_acc_ts);
+    _mav_put_uint64_t(buf, 56, dpl_ts);
+    _mav_put_uint64_t(buf, 64, dpl_max_acc_ts);
+    _mav_put_float(buf, 72, liftoff_max_acc);
+    _mav_put_float(buf, 76, max_speed);
+    _mav_put_float(buf, 80, max_speed_altitude);
+    _mav_put_float(buf, 84, max_mach);
+    _mav_put_float(buf, 88, apogee_lat);
+    _mav_put_float(buf, 92, apogee_lon);
+    _mav_put_float(buf, 96, apogee_alt);
+    _mav_put_float(buf, 100, apogee_max_acc);
+    _mav_put_float(buf, 104, wing_target_lat);
+    _mav_put_float(buf, 108, wing_target_lon);
+    _mav_put_float(buf, 112, wing_active_target_n);
+    _mav_put_float(buf, 116, wing_active_target_e);
     _mav_put_float(buf, 120, dpl_alt);
     _mav_put_float(buf, 124, dpl_max_acc);
     _mav_put_float(buf, 128, ref_lat);
@@ -404,21 +403,23 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack_chan(uint8_t system_id,
     _mav_put_uint32_t(buf, 148, free_heap);
     _mav_put_int32_t(buf, 152, log_good);
     _mav_put_int16_t(buf, 156, log_number);
-    _mav_put_uint8_t(buf, 158, nas_state);
-    _mav_put_uint8_t(buf, 159, wes_state);
-    _mav_put_uint8_t(buf, 160, pin_launch);
-    _mav_put_uint8_t(buf, 161, pin_nosecone);
-    _mav_put_uint8_t(buf, 162, cutter_presence);
-    _mav_put_uint8_t(buf, 163, main_board_state);
-    _mav_put_uint8_t(buf, 164, motor_board_state);
-    _mav_put_uint8_t(buf, 165, main_can_status);
-    _mav_put_uint8_t(buf, 166, motor_can_status);
-    _mav_put_uint8_t(buf, 167, rig_can_status);
-    _mav_put_uint8_t(buf, 168, hil_state);
+    _mav_put_uint8_t(buf, 158, wing_algorithm);
+    _mav_put_uint8_t(buf, 159, nas_state);
+    _mav_put_uint8_t(buf, 160, wnc_state);
+    _mav_put_uint8_t(buf, 161, pin_launch);
+    _mav_put_uint8_t(buf, 162, pin_nosecone);
+    _mav_put_uint8_t(buf, 163, cutter_presence);
+    _mav_put_uint8_t(buf, 164, main_board_state);
+    _mav_put_uint8_t(buf, 165, motor_board_state);
+    _mav_put_uint8_t(buf, 166, main_can_status);
+    _mav_put_uint8_t(buf, 167, motor_can_status);
+    _mav_put_uint8_t(buf, 168, rig_can_status);
+    _mav_put_uint8_t(buf, 169, hil_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
 #else
     mavlink_payload_stats_tm_t packet;
+    packet.timestamp = timestamp;
     packet.liftoff_ts = liftoff_ts;
     packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
     packet.max_speed_ts = max_speed_ts;
@@ -435,12 +436,10 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack_chan(uint8_t system_id,
     packet.apogee_lon = apogee_lon;
     packet.apogee_alt = apogee_alt;
     packet.apogee_max_acc = apogee_max_acc;
-    packet.wing_emc_n = wing_emc_n;
-    packet.wing_emc_e = wing_emc_e;
-    packet.wing_m1_n = wing_m1_n;
-    packet.wing_m1_e = wing_m1_e;
-    packet.wing_m2_n = wing_m2_n;
-    packet.wing_m2_e = wing_m2_e;
+    packet.wing_target_lat = wing_target_lat;
+    packet.wing_target_lon = wing_target_lon;
+    packet.wing_active_target_n = wing_active_target_n;
+    packet.wing_active_target_e = wing_active_target_e;
     packet.dpl_alt = dpl_alt;
     packet.dpl_max_acc = dpl_max_acc;
     packet.ref_lat = ref_lat;
@@ -451,8 +450,9 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack_chan(uint8_t system_id,
     packet.free_heap = free_heap;
     packet.log_good = log_good;
     packet.log_number = log_number;
+    packet.wing_algorithm = wing_algorithm;
     packet.nas_state = nas_state;
-    packet.wes_state = wes_state;
+    packet.wnc_state = wnc_state;
     packet.pin_launch = pin_launch;
     packet.pin_nosecone = pin_nosecone;
     packet.cutter_presence = cutter_presence;
@@ -480,7 +480,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_ts, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->max_speed_ts, payload_stats_tm->max_speed, payload_stats_tm->max_speed_altitude, payload_stats_tm->max_mach_ts, payload_stats_tm->max_mach, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->apogee_max_acc_ts, payload_stats_tm->apogee_max_acc, payload_stats_tm->wing_emc_n, payload_stats_tm->wing_emc_e, payload_stats_tm->wing_m1_n, payload_stats_tm->wing_m1_e, payload_stats_tm->wing_m2_n, payload_stats_tm->wing_m2_e, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_alt, payload_stats_tm->dpl_max_acc_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->ref_lat, payload_stats_tm->ref_lon, payload_stats_tm->ref_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap, payload_stats_tm->nas_state, payload_stats_tm->wes_state, payload_stats_tm->pin_launch, payload_stats_tm->pin_nosecone, payload_stats_tm->cutter_presence, 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);
+    return mavlink_msg_payload_stats_tm_pack(system_id, component_id, msg, payload_stats_tm->timestamp, payload_stats_tm->liftoff_ts, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->max_speed_ts, payload_stats_tm->max_speed, payload_stats_tm->max_speed_altitude, payload_stats_tm->max_mach_ts, payload_stats_tm->max_mach, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->apogee_max_acc_ts, payload_stats_tm->apogee_max_acc, payload_stats_tm->wing_target_lat, payload_stats_tm->wing_target_lon, payload_stats_tm->wing_active_target_n, payload_stats_tm->wing_active_target_e, payload_stats_tm->wing_algorithm, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_alt, payload_stats_tm->dpl_max_acc_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->ref_lat, payload_stats_tm->ref_lon, payload_stats_tm->ref_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap, payload_stats_tm->nas_state, payload_stats_tm->wnc_state, payload_stats_tm->pin_launch, payload_stats_tm->pin_nosecone, payload_stats_tm->cutter_presence, 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);
 }
 
 /**
@@ -494,13 +494,14 @@ 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_ts, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->max_speed_ts, payload_stats_tm->max_speed, payload_stats_tm->max_speed_altitude, payload_stats_tm->max_mach_ts, payload_stats_tm->max_mach, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->apogee_max_acc_ts, payload_stats_tm->apogee_max_acc, payload_stats_tm->wing_emc_n, payload_stats_tm->wing_emc_e, payload_stats_tm->wing_m1_n, payload_stats_tm->wing_m1_e, payload_stats_tm->wing_m2_n, payload_stats_tm->wing_m2_e, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_alt, payload_stats_tm->dpl_max_acc_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->ref_lat, payload_stats_tm->ref_lon, payload_stats_tm->ref_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap, payload_stats_tm->nas_state, payload_stats_tm->wes_state, payload_stats_tm->pin_launch, payload_stats_tm->pin_nosecone, payload_stats_tm->cutter_presence, 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);
+    return mavlink_msg_payload_stats_tm_pack_chan(system_id, component_id, chan, msg, payload_stats_tm->timestamp, payload_stats_tm->liftoff_ts, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->max_speed_ts, payload_stats_tm->max_speed, payload_stats_tm->max_speed_altitude, payload_stats_tm->max_mach_ts, payload_stats_tm->max_mach, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->apogee_max_acc_ts, payload_stats_tm->apogee_max_acc, payload_stats_tm->wing_target_lat, payload_stats_tm->wing_target_lon, payload_stats_tm->wing_active_target_n, payload_stats_tm->wing_active_target_e, payload_stats_tm->wing_algorithm, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_alt, payload_stats_tm->dpl_max_acc_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->ref_lat, payload_stats_tm->ref_lon, payload_stats_tm->ref_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap, payload_stats_tm->nas_state, payload_stats_tm->wnc_state, payload_stats_tm->pin_launch, payload_stats_tm->pin_nosecone, payload_stats_tm->cutter_presence, 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);
 }
 
 /**
  * @brief Send a payload_stats_tm message
  * @param chan MAVLink channel to send the message
  *
+ * @param timestamp [us] Timestamp in microseconds
  * @param liftoff_ts [us] System clock at liftoff
  * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
  * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
@@ -515,12 +516,11 @@ static inline uint16_t mavlink_msg_payload_stats_tm_encode_chan(uint8_t system_i
  * @param apogee_alt [m] Apogee altitude
  * @param apogee_max_acc_ts [us] System clock at max acceleration after apogee
  * @param apogee_max_acc [m/s2] Max acceleration after apogee
- * @param wing_emc_n [m] Wing controller EMC N
- * @param wing_emc_e [m] Wing controller EMC E
- * @param wing_m1_n [m] Wing controller M1 N
- * @param wing_m1_e [m] Wing controller M1 E
- * @param wing_m2_n [m] Wing controller M2 N
- * @param wing_m2_e [m] Wing controller M2 E
+ * @param wing_target_lat [deg] Wing target latitude
+ * @param wing_target_lon [deg] Wing target longitude
+ * @param wing_active_target_n [m] Wing active target N
+ * @param wing_active_target_e [m] Wing active target E
+ * @param wing_algorithm  Wing selected algorithm
  * @param dpl_ts [us] System clock at main deployment
  * @param dpl_alt [m] Deployment altitude
  * @param dpl_max_acc_ts [us] System clock at max acceleration during main deployment
@@ -532,7 +532,7 @@ static inline uint16_t mavlink_msg_payload_stats_tm_encode_chan(uint8_t system_i
  * @param cpu_load  CPU load in percentage
  * @param free_heap  Amount of available heap in memory
  * @param nas_state  NAS FSM State
- * @param wes_state  Wind Estimation System FSM State
+ * @param wnc_state  Wing Controller State
  * @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)
@@ -547,32 +547,31 @@ static inline uint16_t mavlink_msg_payload_stats_tm_encode_chan(uint8_t system_i
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t max_speed_ts, float max_speed, float max_speed_altitude, uint64_t max_mach_ts, float max_mach, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, uint64_t apogee_max_acc_ts, float apogee_max_acc, float wing_emc_n, float wing_emc_e, float wing_m1_n, float wing_m1_e, float wing_m2_n, float wing_m2_e, uint64_t dpl_ts, float dpl_alt, uint64_t dpl_max_acc_ts, float dpl_max_acc, float ref_lat, float ref_lon, float ref_alt, float min_pressure, float cpu_load, uint32_t free_heap, uint8_t nas_state, uint8_t wes_state, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t cutter_presence, 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)
+static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t max_speed_ts, float max_speed, float max_speed_altitude, uint64_t max_mach_ts, float max_mach, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, uint64_t apogee_max_acc_ts, float apogee_max_acc, float wing_target_lat, float wing_target_lon, float wing_active_target_n, float wing_active_target_e, uint8_t wing_algorithm, uint64_t dpl_ts, float dpl_alt, uint64_t dpl_max_acc_ts, float dpl_max_acc, float ref_lat, float ref_lon, float ref_alt, float min_pressure, float cpu_load, uint32_t free_heap, uint8_t nas_state, uint8_t wnc_state, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t cutter_presence, 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];
-    _mav_put_uint64_t(buf, 0, liftoff_ts);
-    _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
-    _mav_put_uint64_t(buf, 16, max_speed_ts);
-    _mav_put_uint64_t(buf, 24, max_mach_ts);
-    _mav_put_uint64_t(buf, 32, apogee_ts);
-    _mav_put_uint64_t(buf, 40, apogee_max_acc_ts);
-    _mav_put_uint64_t(buf, 48, dpl_ts);
-    _mav_put_uint64_t(buf, 56, dpl_max_acc_ts);
-    _mav_put_float(buf, 64, liftoff_max_acc);
-    _mav_put_float(buf, 68, max_speed);
-    _mav_put_float(buf, 72, max_speed_altitude);
-    _mav_put_float(buf, 76, max_mach);
-    _mav_put_float(buf, 80, apogee_lat);
-    _mav_put_float(buf, 84, apogee_lon);
-    _mav_put_float(buf, 88, apogee_alt);
-    _mav_put_float(buf, 92, apogee_max_acc);
-    _mav_put_float(buf, 96, wing_emc_n);
-    _mav_put_float(buf, 100, wing_emc_e);
-    _mav_put_float(buf, 104, wing_m1_n);
-    _mav_put_float(buf, 108, wing_m1_e);
-    _mav_put_float(buf, 112, wing_m2_n);
-    _mav_put_float(buf, 116, wing_m2_e);
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint64_t(buf, 8, liftoff_ts);
+    _mav_put_uint64_t(buf, 16, liftoff_max_acc_ts);
+    _mav_put_uint64_t(buf, 24, max_speed_ts);
+    _mav_put_uint64_t(buf, 32, max_mach_ts);
+    _mav_put_uint64_t(buf, 40, apogee_ts);
+    _mav_put_uint64_t(buf, 48, apogee_max_acc_ts);
+    _mav_put_uint64_t(buf, 56, dpl_ts);
+    _mav_put_uint64_t(buf, 64, dpl_max_acc_ts);
+    _mav_put_float(buf, 72, liftoff_max_acc);
+    _mav_put_float(buf, 76, max_speed);
+    _mav_put_float(buf, 80, max_speed_altitude);
+    _mav_put_float(buf, 84, max_mach);
+    _mav_put_float(buf, 88, apogee_lat);
+    _mav_put_float(buf, 92, apogee_lon);
+    _mav_put_float(buf, 96, apogee_alt);
+    _mav_put_float(buf, 100, apogee_max_acc);
+    _mav_put_float(buf, 104, wing_target_lat);
+    _mav_put_float(buf, 108, wing_target_lon);
+    _mav_put_float(buf, 112, wing_active_target_n);
+    _mav_put_float(buf, 116, wing_active_target_e);
     _mav_put_float(buf, 120, dpl_alt);
     _mav_put_float(buf, 124, dpl_max_acc);
     _mav_put_float(buf, 128, ref_lat);
@@ -583,21 +582,23 @@ static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uin
     _mav_put_uint32_t(buf, 148, free_heap);
     _mav_put_int32_t(buf, 152, log_good);
     _mav_put_int16_t(buf, 156, log_number);
-    _mav_put_uint8_t(buf, 158, nas_state);
-    _mav_put_uint8_t(buf, 159, wes_state);
-    _mav_put_uint8_t(buf, 160, pin_launch);
-    _mav_put_uint8_t(buf, 161, pin_nosecone);
-    _mav_put_uint8_t(buf, 162, cutter_presence);
-    _mav_put_uint8_t(buf, 163, main_board_state);
-    _mav_put_uint8_t(buf, 164, motor_board_state);
-    _mav_put_uint8_t(buf, 165, main_can_status);
-    _mav_put_uint8_t(buf, 166, motor_can_status);
-    _mav_put_uint8_t(buf, 167, rig_can_status);
-    _mav_put_uint8_t(buf, 168, hil_state);
+    _mav_put_uint8_t(buf, 158, wing_algorithm);
+    _mav_put_uint8_t(buf, 159, nas_state);
+    _mav_put_uint8_t(buf, 160, wnc_state);
+    _mav_put_uint8_t(buf, 161, pin_launch);
+    _mav_put_uint8_t(buf, 162, pin_nosecone);
+    _mav_put_uint8_t(buf, 163, cutter_presence);
+    _mav_put_uint8_t(buf, 164, main_board_state);
+    _mav_put_uint8_t(buf, 165, motor_board_state);
+    _mav_put_uint8_t(buf, 166, main_can_status);
+    _mav_put_uint8_t(buf, 167, motor_can_status);
+    _mav_put_uint8_t(buf, 168, rig_can_status);
+    _mav_put_uint8_t(buf, 169, 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
     mavlink_payload_stats_tm_t packet;
+    packet.timestamp = timestamp;
     packet.liftoff_ts = liftoff_ts;
     packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
     packet.max_speed_ts = max_speed_ts;
@@ -614,12 +615,10 @@ static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uin
     packet.apogee_lon = apogee_lon;
     packet.apogee_alt = apogee_alt;
     packet.apogee_max_acc = apogee_max_acc;
-    packet.wing_emc_n = wing_emc_n;
-    packet.wing_emc_e = wing_emc_e;
-    packet.wing_m1_n = wing_m1_n;
-    packet.wing_m1_e = wing_m1_e;
-    packet.wing_m2_n = wing_m2_n;
-    packet.wing_m2_e = wing_m2_e;
+    packet.wing_target_lat = wing_target_lat;
+    packet.wing_target_lon = wing_target_lon;
+    packet.wing_active_target_n = wing_active_target_n;
+    packet.wing_active_target_e = wing_active_target_e;
     packet.dpl_alt = dpl_alt;
     packet.dpl_max_acc = dpl_max_acc;
     packet.ref_lat = ref_lat;
@@ -630,8 +629,9 @@ static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uin
     packet.free_heap = free_heap;
     packet.log_good = log_good;
     packet.log_number = log_number;
+    packet.wing_algorithm = wing_algorithm;
     packet.nas_state = nas_state;
-    packet.wes_state = wes_state;
+    packet.wnc_state = wnc_state;
     packet.pin_launch = pin_launch;
     packet.pin_nosecone = pin_nosecone;
     packet.cutter_presence = cutter_presence;
@@ -654,7 +654,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_ts, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->max_speed_ts, payload_stats_tm->max_speed, payload_stats_tm->max_speed_altitude, payload_stats_tm->max_mach_ts, payload_stats_tm->max_mach, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->apogee_max_acc_ts, payload_stats_tm->apogee_max_acc, payload_stats_tm->wing_emc_n, payload_stats_tm->wing_emc_e, payload_stats_tm->wing_m1_n, payload_stats_tm->wing_m1_e, payload_stats_tm->wing_m2_n, payload_stats_tm->wing_m2_e, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_alt, payload_stats_tm->dpl_max_acc_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->ref_lat, payload_stats_tm->ref_lon, payload_stats_tm->ref_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap, payload_stats_tm->nas_state, payload_stats_tm->wes_state, payload_stats_tm->pin_launch, payload_stats_tm->pin_nosecone, payload_stats_tm->cutter_presence, 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);
+    mavlink_msg_payload_stats_tm_send(chan, payload_stats_tm->timestamp, payload_stats_tm->liftoff_ts, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->max_speed_ts, payload_stats_tm->max_speed, payload_stats_tm->max_speed_altitude, payload_stats_tm->max_mach_ts, payload_stats_tm->max_mach, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->apogee_max_acc_ts, payload_stats_tm->apogee_max_acc, payload_stats_tm->wing_target_lat, payload_stats_tm->wing_target_lon, payload_stats_tm->wing_active_target_n, payload_stats_tm->wing_active_target_e, payload_stats_tm->wing_algorithm, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_alt, payload_stats_tm->dpl_max_acc_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->ref_lat, payload_stats_tm->ref_lon, payload_stats_tm->ref_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap, payload_stats_tm->nas_state, payload_stats_tm->wnc_state, payload_stats_tm->pin_launch, payload_stats_tm->pin_nosecone, payload_stats_tm->cutter_presence, 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
@@ -668,32 +668,31 @@ 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_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t max_speed_ts, float max_speed, float max_speed_altitude, uint64_t max_mach_ts, float max_mach, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, uint64_t apogee_max_acc_ts, float apogee_max_acc, float wing_emc_n, float wing_emc_e, float wing_m1_n, float wing_m1_e, float wing_m2_n, float wing_m2_e, uint64_t dpl_ts, float dpl_alt, uint64_t dpl_max_acc_ts, float dpl_max_acc, float ref_lat, float ref_lon, float ref_alt, float min_pressure, float cpu_load, uint32_t free_heap, uint8_t nas_state, uint8_t wes_state, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t cutter_presence, 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)
+static inline void mavlink_msg_payload_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t max_speed_ts, float max_speed, float max_speed_altitude, uint64_t max_mach_ts, float max_mach, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, uint64_t apogee_max_acc_ts, float apogee_max_acc, float wing_target_lat, float wing_target_lon, float wing_active_target_n, float wing_active_target_e, uint8_t wing_algorithm, uint64_t dpl_ts, float dpl_alt, uint64_t dpl_max_acc_ts, float dpl_max_acc, float ref_lat, float ref_lon, float ref_alt, float min_pressure, float cpu_load, uint32_t free_heap, uint8_t nas_state, uint8_t wnc_state, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t cutter_presence, 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;
-    _mav_put_uint64_t(buf, 0, liftoff_ts);
-    _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
-    _mav_put_uint64_t(buf, 16, max_speed_ts);
-    _mav_put_uint64_t(buf, 24, max_mach_ts);
-    _mav_put_uint64_t(buf, 32, apogee_ts);
-    _mav_put_uint64_t(buf, 40, apogee_max_acc_ts);
-    _mav_put_uint64_t(buf, 48, dpl_ts);
-    _mav_put_uint64_t(buf, 56, dpl_max_acc_ts);
-    _mav_put_float(buf, 64, liftoff_max_acc);
-    _mav_put_float(buf, 68, max_speed);
-    _mav_put_float(buf, 72, max_speed_altitude);
-    _mav_put_float(buf, 76, max_mach);
-    _mav_put_float(buf, 80, apogee_lat);
-    _mav_put_float(buf, 84, apogee_lon);
-    _mav_put_float(buf, 88, apogee_alt);
-    _mav_put_float(buf, 92, apogee_max_acc);
-    _mav_put_float(buf, 96, wing_emc_n);
-    _mav_put_float(buf, 100, wing_emc_e);
-    _mav_put_float(buf, 104, wing_m1_n);
-    _mav_put_float(buf, 108, wing_m1_e);
-    _mav_put_float(buf, 112, wing_m2_n);
-    _mav_put_float(buf, 116, wing_m2_e);
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_uint64_t(buf, 8, liftoff_ts);
+    _mav_put_uint64_t(buf, 16, liftoff_max_acc_ts);
+    _mav_put_uint64_t(buf, 24, max_speed_ts);
+    _mav_put_uint64_t(buf, 32, max_mach_ts);
+    _mav_put_uint64_t(buf, 40, apogee_ts);
+    _mav_put_uint64_t(buf, 48, apogee_max_acc_ts);
+    _mav_put_uint64_t(buf, 56, dpl_ts);
+    _mav_put_uint64_t(buf, 64, dpl_max_acc_ts);
+    _mav_put_float(buf, 72, liftoff_max_acc);
+    _mav_put_float(buf, 76, max_speed);
+    _mav_put_float(buf, 80, max_speed_altitude);
+    _mav_put_float(buf, 84, max_mach);
+    _mav_put_float(buf, 88, apogee_lat);
+    _mav_put_float(buf, 92, apogee_lon);
+    _mav_put_float(buf, 96, apogee_alt);
+    _mav_put_float(buf, 100, apogee_max_acc);
+    _mav_put_float(buf, 104, wing_target_lat);
+    _mav_put_float(buf, 108, wing_target_lon);
+    _mav_put_float(buf, 112, wing_active_target_n);
+    _mav_put_float(buf, 116, wing_active_target_e);
     _mav_put_float(buf, 120, dpl_alt);
     _mav_put_float(buf, 124, dpl_max_acc);
     _mav_put_float(buf, 128, ref_lat);
@@ -704,21 +703,23 @@ static inline void mavlink_msg_payload_stats_tm_send_buf(mavlink_message_t *msgb
     _mav_put_uint32_t(buf, 148, free_heap);
     _mav_put_int32_t(buf, 152, log_good);
     _mav_put_int16_t(buf, 156, log_number);
-    _mav_put_uint8_t(buf, 158, nas_state);
-    _mav_put_uint8_t(buf, 159, wes_state);
-    _mav_put_uint8_t(buf, 160, pin_launch);
-    _mav_put_uint8_t(buf, 161, pin_nosecone);
-    _mav_put_uint8_t(buf, 162, cutter_presence);
-    _mav_put_uint8_t(buf, 163, main_board_state);
-    _mav_put_uint8_t(buf, 164, motor_board_state);
-    _mav_put_uint8_t(buf, 165, main_can_status);
-    _mav_put_uint8_t(buf, 166, motor_can_status);
-    _mav_put_uint8_t(buf, 167, rig_can_status);
-    _mav_put_uint8_t(buf, 168, hil_state);
+    _mav_put_uint8_t(buf, 158, wing_algorithm);
+    _mav_put_uint8_t(buf, 159, nas_state);
+    _mav_put_uint8_t(buf, 160, wnc_state);
+    _mav_put_uint8_t(buf, 161, pin_launch);
+    _mav_put_uint8_t(buf, 162, pin_nosecone);
+    _mav_put_uint8_t(buf, 163, cutter_presence);
+    _mav_put_uint8_t(buf, 164, main_board_state);
+    _mav_put_uint8_t(buf, 165, motor_board_state);
+    _mav_put_uint8_t(buf, 166, main_can_status);
+    _mav_put_uint8_t(buf, 167, motor_can_status);
+    _mav_put_uint8_t(buf, 168, rig_can_status);
+    _mav_put_uint8_t(buf, 169, 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
     mavlink_payload_stats_tm_t *packet = (mavlink_payload_stats_tm_t *)msgbuf;
+    packet->timestamp = timestamp;
     packet->liftoff_ts = liftoff_ts;
     packet->liftoff_max_acc_ts = liftoff_max_acc_ts;
     packet->max_speed_ts = max_speed_ts;
@@ -735,12 +736,10 @@ static inline void mavlink_msg_payload_stats_tm_send_buf(mavlink_message_t *msgb
     packet->apogee_lon = apogee_lon;
     packet->apogee_alt = apogee_alt;
     packet->apogee_max_acc = apogee_max_acc;
-    packet->wing_emc_n = wing_emc_n;
-    packet->wing_emc_e = wing_emc_e;
-    packet->wing_m1_n = wing_m1_n;
-    packet->wing_m1_e = wing_m1_e;
-    packet->wing_m2_n = wing_m2_n;
-    packet->wing_m2_e = wing_m2_e;
+    packet->wing_target_lat = wing_target_lat;
+    packet->wing_target_lon = wing_target_lon;
+    packet->wing_active_target_n = wing_active_target_n;
+    packet->wing_active_target_e = wing_active_target_e;
     packet->dpl_alt = dpl_alt;
     packet->dpl_max_acc = dpl_max_acc;
     packet->ref_lat = ref_lat;
@@ -751,8 +750,9 @@ static inline void mavlink_msg_payload_stats_tm_send_buf(mavlink_message_t *msgb
     packet->free_heap = free_heap;
     packet->log_good = log_good;
     packet->log_number = log_number;
+    packet->wing_algorithm = wing_algorithm;
     packet->nas_state = nas_state;
-    packet->wes_state = wes_state;
+    packet->wnc_state = wnc_state;
     packet->pin_launch = pin_launch;
     packet->pin_nosecone = pin_nosecone;
     packet->cutter_presence = cutter_presence;
@@ -773,6 +773,16 @@ static inline void mavlink_msg_payload_stats_tm_send_buf(mavlink_message_t *msgb
 // MESSAGE PAYLOAD_STATS_TM UNPACKING
 
 
+/**
+ * @brief Get field timestamp from payload_stats_tm message
+ *
+ * @return [us] Timestamp in microseconds
+ */
+static inline uint64_t mavlink_msg_payload_stats_tm_get_timestamp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint64_t(msg,  0);
+}
+
 /**
  * @brief Get field liftoff_ts from payload_stats_tm message
  *
@@ -780,7 +790,7 @@ static inline void mavlink_msg_payload_stats_tm_send_buf(mavlink_message_t *msgb
  */
 static inline uint64_t mavlink_msg_payload_stats_tm_get_liftoff_ts(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint64_t(msg,  0);
+    return _MAV_RETURN_uint64_t(msg,  8);
 }
 
 /**
@@ -790,7 +800,7 @@ static inline uint64_t mavlink_msg_payload_stats_tm_get_liftoff_ts(const mavlink
  */
 static inline uint64_t mavlink_msg_payload_stats_tm_get_liftoff_max_acc_ts(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint64_t(msg,  8);
+    return _MAV_RETURN_uint64_t(msg,  16);
 }
 
 /**
@@ -800,7 +810,7 @@ static inline uint64_t mavlink_msg_payload_stats_tm_get_liftoff_max_acc_ts(const
  */
 static inline float mavlink_msg_payload_stats_tm_get_liftoff_max_acc(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  64);
+    return _MAV_RETURN_float(msg,  72);
 }
 
 /**
@@ -810,7 +820,7 @@ static inline float mavlink_msg_payload_stats_tm_get_liftoff_max_acc(const mavli
  */
 static inline uint64_t mavlink_msg_payload_stats_tm_get_max_speed_ts(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint64_t(msg,  16);
+    return _MAV_RETURN_uint64_t(msg,  24);
 }
 
 /**
@@ -820,7 +830,7 @@ static inline uint64_t mavlink_msg_payload_stats_tm_get_max_speed_ts(const mavli
  */
 static inline float mavlink_msg_payload_stats_tm_get_max_speed(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  68);
+    return _MAV_RETURN_float(msg,  76);
 }
 
 /**
@@ -830,7 +840,7 @@ static inline float mavlink_msg_payload_stats_tm_get_max_speed(const mavlink_mes
  */
 static inline float mavlink_msg_payload_stats_tm_get_max_speed_altitude(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  72);
+    return _MAV_RETURN_float(msg,  80);
 }
 
 /**
@@ -840,7 +850,7 @@ static inline float mavlink_msg_payload_stats_tm_get_max_speed_altitude(const ma
  */
 static inline uint64_t mavlink_msg_payload_stats_tm_get_max_mach_ts(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint64_t(msg,  24);
+    return _MAV_RETURN_uint64_t(msg,  32);
 }
 
 /**
@@ -850,7 +860,7 @@ static inline uint64_t mavlink_msg_payload_stats_tm_get_max_mach_ts(const mavlin
  */
 static inline float mavlink_msg_payload_stats_tm_get_max_mach(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  76);
+    return _MAV_RETURN_float(msg,  84);
 }
 
 /**
@@ -860,7 +870,7 @@ static inline float mavlink_msg_payload_stats_tm_get_max_mach(const mavlink_mess
  */
 static inline uint64_t mavlink_msg_payload_stats_tm_get_apogee_ts(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint64_t(msg,  32);
+    return _MAV_RETURN_uint64_t(msg,  40);
 }
 
 /**
@@ -870,7 +880,7 @@ static inline uint64_t mavlink_msg_payload_stats_tm_get_apogee_ts(const mavlink_
  */
 static inline float mavlink_msg_payload_stats_tm_get_apogee_lat(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  80);
+    return _MAV_RETURN_float(msg,  88);
 }
 
 /**
@@ -880,7 +890,7 @@ static inline float mavlink_msg_payload_stats_tm_get_apogee_lat(const mavlink_me
  */
 static inline float mavlink_msg_payload_stats_tm_get_apogee_lon(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  84);
+    return _MAV_RETURN_float(msg,  92);
 }
 
 /**
@@ -890,7 +900,7 @@ static inline float mavlink_msg_payload_stats_tm_get_apogee_lon(const mavlink_me
  */
 static inline float mavlink_msg_payload_stats_tm_get_apogee_alt(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  88);
+    return _MAV_RETURN_float(msg,  96);
 }
 
 /**
@@ -900,7 +910,7 @@ static inline float mavlink_msg_payload_stats_tm_get_apogee_alt(const mavlink_me
  */
 static inline uint64_t mavlink_msg_payload_stats_tm_get_apogee_max_acc_ts(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint64_t(msg,  40);
+    return _MAV_RETURN_uint64_t(msg,  48);
 }
 
 /**
@@ -910,67 +920,57 @@ static inline uint64_t mavlink_msg_payload_stats_tm_get_apogee_max_acc_ts(const
  */
 static inline float mavlink_msg_payload_stats_tm_get_apogee_max_acc(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  92);
-}
-
-/**
- * @brief Get field wing_emc_n from payload_stats_tm message
- *
- * @return [m] Wing controller EMC N
- */
-static inline float mavlink_msg_payload_stats_tm_get_wing_emc_n(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_float(msg,  96);
+    return _MAV_RETURN_float(msg,  100);
 }
 
 /**
- * @brief Get field wing_emc_e from payload_stats_tm message
+ * @brief Get field wing_target_lat from payload_stats_tm message
  *
- * @return [m] Wing controller EMC E
+ * @return [deg] Wing target latitude
  */
-static inline float mavlink_msg_payload_stats_tm_get_wing_emc_e(const mavlink_message_t* msg)
+static inline float mavlink_msg_payload_stats_tm_get_wing_target_lat(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  100);
+    return _MAV_RETURN_float(msg,  104);
 }
 
 /**
- * @brief Get field wing_m1_n from payload_stats_tm message
+ * @brief Get field wing_target_lon from payload_stats_tm message
  *
- * @return [m] Wing controller M1 N
+ * @return [deg] Wing target longitude
  */
-static inline float mavlink_msg_payload_stats_tm_get_wing_m1_n(const mavlink_message_t* msg)
+static inline float mavlink_msg_payload_stats_tm_get_wing_target_lon(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  104);
+    return _MAV_RETURN_float(msg,  108);
 }
 
 /**
- * @brief Get field wing_m1_e from payload_stats_tm message
+ * @brief Get field wing_active_target_n from payload_stats_tm message
  *
- * @return [m] Wing controller M1 E
+ * @return [m] Wing active target N
  */
-static inline float mavlink_msg_payload_stats_tm_get_wing_m1_e(const mavlink_message_t* msg)
+static inline float mavlink_msg_payload_stats_tm_get_wing_active_target_n(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  108);
+    return _MAV_RETURN_float(msg,  112);
 }
 
 /**
- * @brief Get field wing_m2_n from payload_stats_tm message
+ * @brief Get field wing_active_target_e from payload_stats_tm message
  *
- * @return [m] Wing controller M2 N
+ * @return [m] Wing active target E
  */
-static inline float mavlink_msg_payload_stats_tm_get_wing_m2_n(const mavlink_message_t* msg)
+static inline float mavlink_msg_payload_stats_tm_get_wing_active_target_e(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  112);
+    return _MAV_RETURN_float(msg,  116);
 }
 
 /**
- * @brief Get field wing_m2_e from payload_stats_tm message
+ * @brief Get field wing_algorithm from payload_stats_tm message
  *
- * @return [m] Wing controller M2 E
+ * @return  Wing selected algorithm
  */
-static inline float mavlink_msg_payload_stats_tm_get_wing_m2_e(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_payload_stats_tm_get_wing_algorithm(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  116);
+    return _MAV_RETURN_uint8_t(msg,  158);
 }
 
 /**
@@ -980,7 +980,7 @@ static inline float mavlink_msg_payload_stats_tm_get_wing_m2_e(const mavlink_mes
  */
 static inline uint64_t mavlink_msg_payload_stats_tm_get_dpl_ts(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint64_t(msg,  48);
+    return _MAV_RETURN_uint64_t(msg,  56);
 }
 
 /**
@@ -1000,7 +1000,7 @@ static inline float mavlink_msg_payload_stats_tm_get_dpl_alt(const mavlink_messa
  */
 static inline uint64_t mavlink_msg_payload_stats_tm_get_dpl_max_acc_ts(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint64_t(msg,  56);
+    return _MAV_RETURN_uint64_t(msg,  64);
 }
 
 /**
@@ -1080,17 +1080,17 @@ static inline uint32_t mavlink_msg_payload_stats_tm_get_free_heap(const mavlink_
  */
 static inline uint8_t mavlink_msg_payload_stats_tm_get_nas_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  158);
+    return _MAV_RETURN_uint8_t(msg,  159);
 }
 
 /**
- * @brief Get field wes_state from payload_stats_tm message
+ * @brief Get field wnc_state from payload_stats_tm message
  *
- * @return  Wind Estimation System FSM State
+ * @return  Wing Controller State
  */
-static inline uint8_t mavlink_msg_payload_stats_tm_get_wes_state(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_payload_stats_tm_get_wnc_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  159);
+    return _MAV_RETURN_uint8_t(msg,  160);
 }
 
 /**
@@ -1100,7 +1100,7 @@ static inline uint8_t mavlink_msg_payload_stats_tm_get_wes_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_payload_stats_tm_get_pin_launch(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  160);
+    return _MAV_RETURN_uint8_t(msg,  161);
 }
 
 /**
@@ -1110,7 +1110,7 @@ static inline uint8_t mavlink_msg_payload_stats_tm_get_pin_launch(const mavlink_
  */
 static inline uint8_t mavlink_msg_payload_stats_tm_get_pin_nosecone(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  161);
+    return _MAV_RETURN_uint8_t(msg,  162);
 }
 
 /**
@@ -1120,7 +1120,7 @@ static inline uint8_t mavlink_msg_payload_stats_tm_get_pin_nosecone(const mavlin
  */
 static inline uint8_t mavlink_msg_payload_stats_tm_get_cutter_presence(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  162);
+    return _MAV_RETURN_uint8_t(msg,  163);
 }
 
 /**
@@ -1150,7 +1150,7 @@ static inline int32_t mavlink_msg_payload_stats_tm_get_log_good(const mavlink_me
  */
 static inline uint8_t mavlink_msg_payload_stats_tm_get_main_board_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  163);
+    return _MAV_RETURN_uint8_t(msg,  164);
 }
 
 /**
@@ -1160,7 +1160,7 @@ static inline uint8_t mavlink_msg_payload_stats_tm_get_main_board_state(const ma
  */
 static inline uint8_t mavlink_msg_payload_stats_tm_get_motor_board_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  164);
+    return _MAV_RETURN_uint8_t(msg,  165);
 }
 
 /**
@@ -1170,7 +1170,7 @@ static inline uint8_t mavlink_msg_payload_stats_tm_get_motor_board_state(const m
  */
 static inline uint8_t mavlink_msg_payload_stats_tm_get_main_can_status(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  165);
+    return _MAV_RETURN_uint8_t(msg,  166);
 }
 
 /**
@@ -1180,7 +1180,7 @@ static inline uint8_t mavlink_msg_payload_stats_tm_get_main_can_status(const mav
  */
 static inline uint8_t mavlink_msg_payload_stats_tm_get_motor_can_status(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  166);
+    return _MAV_RETURN_uint8_t(msg,  167);
 }
 
 /**
@@ -1190,7 +1190,7 @@ static inline uint8_t mavlink_msg_payload_stats_tm_get_motor_can_status(const ma
  */
 static inline uint8_t mavlink_msg_payload_stats_tm_get_rig_can_status(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  167);
+    return _MAV_RETURN_uint8_t(msg,  168);
 }
 
 /**
@@ -1200,7 +1200,7 @@ static inline uint8_t mavlink_msg_payload_stats_tm_get_rig_can_status(const mavl
  */
 static inline uint8_t mavlink_msg_payload_stats_tm_get_hil_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  168);
+    return _MAV_RETURN_uint8_t(msg,  169);
 }
 
 /**
@@ -1212,6 +1212,7 @@ static inline uint8_t mavlink_msg_payload_stats_tm_get_hil_state(const mavlink_m
 static inline void mavlink_msg_payload_stats_tm_decode(const mavlink_message_t* msg, mavlink_payload_stats_tm_t* payload_stats_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    payload_stats_tm->timestamp = mavlink_msg_payload_stats_tm_get_timestamp(msg);
     payload_stats_tm->liftoff_ts = mavlink_msg_payload_stats_tm_get_liftoff_ts(msg);
     payload_stats_tm->liftoff_max_acc_ts = mavlink_msg_payload_stats_tm_get_liftoff_max_acc_ts(msg);
     payload_stats_tm->max_speed_ts = mavlink_msg_payload_stats_tm_get_max_speed_ts(msg);
@@ -1228,12 +1229,10 @@ static inline void mavlink_msg_payload_stats_tm_decode(const mavlink_message_t*
     payload_stats_tm->apogee_lon = mavlink_msg_payload_stats_tm_get_apogee_lon(msg);
     payload_stats_tm->apogee_alt = mavlink_msg_payload_stats_tm_get_apogee_alt(msg);
     payload_stats_tm->apogee_max_acc = mavlink_msg_payload_stats_tm_get_apogee_max_acc(msg);
-    payload_stats_tm->wing_emc_n = mavlink_msg_payload_stats_tm_get_wing_emc_n(msg);
-    payload_stats_tm->wing_emc_e = mavlink_msg_payload_stats_tm_get_wing_emc_e(msg);
-    payload_stats_tm->wing_m1_n = mavlink_msg_payload_stats_tm_get_wing_m1_n(msg);
-    payload_stats_tm->wing_m1_e = mavlink_msg_payload_stats_tm_get_wing_m1_e(msg);
-    payload_stats_tm->wing_m2_n = mavlink_msg_payload_stats_tm_get_wing_m2_n(msg);
-    payload_stats_tm->wing_m2_e = mavlink_msg_payload_stats_tm_get_wing_m2_e(msg);
+    payload_stats_tm->wing_target_lat = mavlink_msg_payload_stats_tm_get_wing_target_lat(msg);
+    payload_stats_tm->wing_target_lon = mavlink_msg_payload_stats_tm_get_wing_target_lon(msg);
+    payload_stats_tm->wing_active_target_n = mavlink_msg_payload_stats_tm_get_wing_active_target_n(msg);
+    payload_stats_tm->wing_active_target_e = mavlink_msg_payload_stats_tm_get_wing_active_target_e(msg);
     payload_stats_tm->dpl_alt = mavlink_msg_payload_stats_tm_get_dpl_alt(msg);
     payload_stats_tm->dpl_max_acc = mavlink_msg_payload_stats_tm_get_dpl_max_acc(msg);
     payload_stats_tm->ref_lat = mavlink_msg_payload_stats_tm_get_ref_lat(msg);
@@ -1244,8 +1243,9 @@ static inline void mavlink_msg_payload_stats_tm_decode(const mavlink_message_t*
     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->wing_algorithm = mavlink_msg_payload_stats_tm_get_wing_algorithm(msg);
     payload_stats_tm->nas_state = mavlink_msg_payload_stats_tm_get_nas_state(msg);
-    payload_stats_tm->wes_state = mavlink_msg_payload_stats_tm_get_wes_state(msg);
+    payload_stats_tm->wnc_state = mavlink_msg_payload_stats_tm_get_wnc_state(msg);
     payload_stats_tm->pin_launch = mavlink_msg_payload_stats_tm_get_pin_launch(msg);
     payload_stats_tm->pin_nosecone = mavlink_msg_payload_stats_tm_get_pin_nosecone(msg);
     payload_stats_tm->cutter_presence = mavlink_msg_payload_stats_tm_get_cutter_presence(msg);
diff --git a/mavlink_lib/lyra/mavlink_msg_wing_tm.h b/mavlink_lib/lyra/mavlink_msg_wing_tm.h
new file mode 100644
index 0000000000000000000000000000000000000000..22a0901381fe99618a2a7f8ae9ce793364a9de45
--- /dev/null
+++ b/mavlink_lib/lyra/mavlink_msg_wing_tm.h
@@ -0,0 +1,463 @@
+#pragma once
+// MESSAGE WING_TM PACKING
+
+#define MAVLINK_MSG_ID_WING_TM 215
+
+
+typedef struct __mavlink_wing_tm_t {
+ uint64_t timestamp; /*< [us] Timestamp in microseconds*/
+ float target_lat; /*< [deg] Target latitude*/
+ float target_lon; /*< [deg] Target longitude*/
+ float target_n; /*< [m] Target N*/
+ float target_e; /*< [m] Target E*/
+ float emc_n; /*< [m] EMC N*/
+ float emc_e; /*< [m] EMC E*/
+ float m1_n; /*< [m] M1 N*/
+ float m1_e; /*< [m] M1 E*/
+ float m2_n; /*< [m] M2 N*/
+ float m2_e; /*< [m] M2 E*/
+} mavlink_wing_tm_t;
+
+#define MAVLINK_MSG_ID_WING_TM_LEN 48
+#define MAVLINK_MSG_ID_WING_TM_MIN_LEN 48
+#define MAVLINK_MSG_ID_215_LEN 48
+#define MAVLINK_MSG_ID_215_MIN_LEN 48
+
+#define MAVLINK_MSG_ID_WING_TM_CRC 113
+#define MAVLINK_MSG_ID_215_CRC 113
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_WING_TM { \
+    215, \
+    "WING_TM", \
+    11, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wing_tm_t, timestamp) }, \
+         { "target_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wing_tm_t, target_lat) }, \
+         { "target_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_wing_tm_t, target_lon) }, \
+         { "target_n", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_wing_tm_t, target_n) }, \
+         { "target_e", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_wing_tm_t, target_e) }, \
+         { "emc_n", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_wing_tm_t, emc_n) }, \
+         { "emc_e", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_wing_tm_t, emc_e) }, \
+         { "m1_n", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_wing_tm_t, m1_n) }, \
+         { "m1_e", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_wing_tm_t, m1_e) }, \
+         { "m2_n", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_wing_tm_t, m2_n) }, \
+         { "m2_e", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_wing_tm_t, m2_e) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_WING_TM { \
+    "WING_TM", \
+    11, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wing_tm_t, timestamp) }, \
+         { "target_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wing_tm_t, target_lat) }, \
+         { "target_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_wing_tm_t, target_lon) }, \
+         { "target_n", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_wing_tm_t, target_n) }, \
+         { "target_e", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_wing_tm_t, target_e) }, \
+         { "emc_n", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_wing_tm_t, emc_n) }, \
+         { "emc_e", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_wing_tm_t, emc_e) }, \
+         { "m1_n", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_wing_tm_t, m1_n) }, \
+         { "m1_e", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_wing_tm_t, m1_e) }, \
+         { "m2_n", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_wing_tm_t, m2_n) }, \
+         { "m2_e", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_wing_tm_t, m2_e) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a wing_tm message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param timestamp [us] Timestamp in microseconds
+ * @param target_lat [deg] Target latitude
+ * @param target_lon [deg] Target longitude
+ * @param target_n [m] Target N
+ * @param target_e [m] Target E
+ * @param emc_n [m] EMC N
+ * @param emc_e [m] EMC E
+ * @param m1_n [m] M1 N
+ * @param m1_e [m] M1 E
+ * @param m2_n [m] M2 N
+ * @param m2_e [m] M2 E
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_wing_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint64_t timestamp, float target_lat, float target_lon, float target_n, float target_e, float emc_n, float emc_e, float m1_n, float m1_e, float m2_n, float m2_e)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_WING_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, target_lat);
+    _mav_put_float(buf, 12, target_lon);
+    _mav_put_float(buf, 16, target_n);
+    _mav_put_float(buf, 20, target_e);
+    _mav_put_float(buf, 24, emc_n);
+    _mav_put_float(buf, 28, emc_e);
+    _mav_put_float(buf, 32, m1_n);
+    _mav_put_float(buf, 36, m1_e);
+    _mav_put_float(buf, 40, m2_n);
+    _mav_put_float(buf, 44, m2_e);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WING_TM_LEN);
+#else
+    mavlink_wing_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.target_lat = target_lat;
+    packet.target_lon = target_lon;
+    packet.target_n = target_n;
+    packet.target_e = target_e;
+    packet.emc_n = emc_n;
+    packet.emc_e = emc_e;
+    packet.m1_n = m1_n;
+    packet.m1_e = m1_e;
+    packet.m2_n = m2_n;
+    packet.m2_e = m2_e;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WING_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_WING_TM;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WING_TM_MIN_LEN, MAVLINK_MSG_ID_WING_TM_LEN, MAVLINK_MSG_ID_WING_TM_CRC);
+}
+
+/**
+ * @brief Pack a wing_tm message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param timestamp [us] Timestamp in microseconds
+ * @param target_lat [deg] Target latitude
+ * @param target_lon [deg] Target longitude
+ * @param target_n [m] Target N
+ * @param target_e [m] Target E
+ * @param emc_n [m] EMC N
+ * @param emc_e [m] EMC E
+ * @param m1_n [m] M1 N
+ * @param m1_e [m] M1 E
+ * @param m2_n [m] M2 N
+ * @param m2_e [m] M2 E
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_wing_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint64_t timestamp,float target_lat,float target_lon,float target_n,float target_e,float emc_n,float emc_e,float m1_n,float m1_e,float m2_n,float m2_e)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_WING_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, target_lat);
+    _mav_put_float(buf, 12, target_lon);
+    _mav_put_float(buf, 16, target_n);
+    _mav_put_float(buf, 20, target_e);
+    _mav_put_float(buf, 24, emc_n);
+    _mav_put_float(buf, 28, emc_e);
+    _mav_put_float(buf, 32, m1_n);
+    _mav_put_float(buf, 36, m1_e);
+    _mav_put_float(buf, 40, m2_n);
+    _mav_put_float(buf, 44, m2_e);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WING_TM_LEN);
+#else
+    mavlink_wing_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.target_lat = target_lat;
+    packet.target_lon = target_lon;
+    packet.target_n = target_n;
+    packet.target_e = target_e;
+    packet.emc_n = emc_n;
+    packet.emc_e = emc_e;
+    packet.m1_n = m1_n;
+    packet.m1_e = m1_e;
+    packet.m2_n = m2_n;
+    packet.m2_e = m2_e;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WING_TM_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_WING_TM;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WING_TM_MIN_LEN, MAVLINK_MSG_ID_WING_TM_LEN, MAVLINK_MSG_ID_WING_TM_CRC);
+}
+
+/**
+ * @brief Encode a wing_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 wing_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_wing_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wing_tm_t* wing_tm)
+{
+    return mavlink_msg_wing_tm_pack(system_id, component_id, msg, wing_tm->timestamp, wing_tm->target_lat, wing_tm->target_lon, wing_tm->target_n, wing_tm->target_e, wing_tm->emc_n, wing_tm->emc_e, wing_tm->m1_n, wing_tm->m1_e, wing_tm->m2_n, wing_tm->m2_e);
+}
+
+/**
+ * @brief Encode a wing_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 wing_tm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_wing_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wing_tm_t* wing_tm)
+{
+    return mavlink_msg_wing_tm_pack_chan(system_id, component_id, chan, msg, wing_tm->timestamp, wing_tm->target_lat, wing_tm->target_lon, wing_tm->target_n, wing_tm->target_e, wing_tm->emc_n, wing_tm->emc_e, wing_tm->m1_n, wing_tm->m1_e, wing_tm->m2_n, wing_tm->m2_e);
+}
+
+/**
+ * @brief Send a wing_tm message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param timestamp [us] Timestamp in microseconds
+ * @param target_lat [deg] Target latitude
+ * @param target_lon [deg] Target longitude
+ * @param target_n [m] Target N
+ * @param target_e [m] Target E
+ * @param emc_n [m] EMC N
+ * @param emc_e [m] EMC E
+ * @param m1_n [m] M1 N
+ * @param m1_e [m] M1 E
+ * @param m2_n [m] M2 N
+ * @param m2_e [m] M2 E
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_wing_tm_send(mavlink_channel_t chan, uint64_t timestamp, float target_lat, float target_lon, float target_n, float target_e, float emc_n, float emc_e, float m1_n, float m1_e, float m2_n, float m2_e)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_WING_TM_LEN];
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, target_lat);
+    _mav_put_float(buf, 12, target_lon);
+    _mav_put_float(buf, 16, target_n);
+    _mav_put_float(buf, 20, target_e);
+    _mav_put_float(buf, 24, emc_n);
+    _mav_put_float(buf, 28, emc_e);
+    _mav_put_float(buf, 32, m1_n);
+    _mav_put_float(buf, 36, m1_e);
+    _mav_put_float(buf, 40, m2_n);
+    _mav_put_float(buf, 44, m2_e);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WING_TM, buf, MAVLINK_MSG_ID_WING_TM_MIN_LEN, MAVLINK_MSG_ID_WING_TM_LEN, MAVLINK_MSG_ID_WING_TM_CRC);
+#else
+    mavlink_wing_tm_t packet;
+    packet.timestamp = timestamp;
+    packet.target_lat = target_lat;
+    packet.target_lon = target_lon;
+    packet.target_n = target_n;
+    packet.target_e = target_e;
+    packet.emc_n = emc_n;
+    packet.emc_e = emc_e;
+    packet.m1_n = m1_n;
+    packet.m1_e = m1_e;
+    packet.m2_n = m2_n;
+    packet.m2_e = m2_e;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WING_TM, (const char *)&packet, MAVLINK_MSG_ID_WING_TM_MIN_LEN, MAVLINK_MSG_ID_WING_TM_LEN, MAVLINK_MSG_ID_WING_TM_CRC);
+#endif
+}
+
+/**
+ * @brief Send a wing_tm message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_wing_tm_send_struct(mavlink_channel_t chan, const mavlink_wing_tm_t* wing_tm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_wing_tm_send(chan, wing_tm->timestamp, wing_tm->target_lat, wing_tm->target_lon, wing_tm->target_n, wing_tm->target_e, wing_tm->emc_n, wing_tm->emc_e, wing_tm->m1_n, wing_tm->m1_e, wing_tm->m2_n, wing_tm->m2_e);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WING_TM, (const char *)wing_tm, MAVLINK_MSG_ID_WING_TM_MIN_LEN, MAVLINK_MSG_ID_WING_TM_LEN, MAVLINK_MSG_ID_WING_TM_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_WING_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_wing_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, float target_lat, float target_lon, float target_n, float target_e, float emc_n, float emc_e, float m1_n, float m1_e, float m2_n, float m2_e)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint64_t(buf, 0, timestamp);
+    _mav_put_float(buf, 8, target_lat);
+    _mav_put_float(buf, 12, target_lon);
+    _mav_put_float(buf, 16, target_n);
+    _mav_put_float(buf, 20, target_e);
+    _mav_put_float(buf, 24, emc_n);
+    _mav_put_float(buf, 28, emc_e);
+    _mav_put_float(buf, 32, m1_n);
+    _mav_put_float(buf, 36, m1_e);
+    _mav_put_float(buf, 40, m2_n);
+    _mav_put_float(buf, 44, m2_e);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WING_TM, buf, MAVLINK_MSG_ID_WING_TM_MIN_LEN, MAVLINK_MSG_ID_WING_TM_LEN, MAVLINK_MSG_ID_WING_TM_CRC);
+#else
+    mavlink_wing_tm_t *packet = (mavlink_wing_tm_t *)msgbuf;
+    packet->timestamp = timestamp;
+    packet->target_lat = target_lat;
+    packet->target_lon = target_lon;
+    packet->target_n = target_n;
+    packet->target_e = target_e;
+    packet->emc_n = emc_n;
+    packet->emc_e = emc_e;
+    packet->m1_n = m1_n;
+    packet->m1_e = m1_e;
+    packet->m2_n = m2_n;
+    packet->m2_e = m2_e;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WING_TM, (const char *)packet, MAVLINK_MSG_ID_WING_TM_MIN_LEN, MAVLINK_MSG_ID_WING_TM_LEN, MAVLINK_MSG_ID_WING_TM_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE WING_TM UNPACKING
+
+
+/**
+ * @brief Get field timestamp from wing_tm message
+ *
+ * @return [us] Timestamp in microseconds
+ */
+static inline uint64_t mavlink_msg_wing_tm_get_timestamp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint64_t(msg,  0);
+}
+
+/**
+ * @brief Get field target_lat from wing_tm message
+ *
+ * @return [deg] Target latitude
+ */
+static inline float mavlink_msg_wing_tm_get_target_lat(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  8);
+}
+
+/**
+ * @brief Get field target_lon from wing_tm message
+ *
+ * @return [deg] Target longitude
+ */
+static inline float mavlink_msg_wing_tm_get_target_lon(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  12);
+}
+
+/**
+ * @brief Get field target_n from wing_tm message
+ *
+ * @return [m] Target N
+ */
+static inline float mavlink_msg_wing_tm_get_target_n(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  16);
+}
+
+/**
+ * @brief Get field target_e from wing_tm message
+ *
+ * @return [m] Target E
+ */
+static inline float mavlink_msg_wing_tm_get_target_e(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  20);
+}
+
+/**
+ * @brief Get field emc_n from wing_tm message
+ *
+ * @return [m] EMC N
+ */
+static inline float mavlink_msg_wing_tm_get_emc_n(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  24);
+}
+
+/**
+ * @brief Get field emc_e from wing_tm message
+ *
+ * @return [m] EMC E
+ */
+static inline float mavlink_msg_wing_tm_get_emc_e(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  28);
+}
+
+/**
+ * @brief Get field m1_n from wing_tm message
+ *
+ * @return [m] M1 N
+ */
+static inline float mavlink_msg_wing_tm_get_m1_n(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  32);
+}
+
+/**
+ * @brief Get field m1_e from wing_tm message
+ *
+ * @return [m] M1 E
+ */
+static inline float mavlink_msg_wing_tm_get_m1_e(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  36);
+}
+
+/**
+ * @brief Get field m2_n from wing_tm message
+ *
+ * @return [m] M2 N
+ */
+static inline float mavlink_msg_wing_tm_get_m2_n(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  40);
+}
+
+/**
+ * @brief Get field m2_e from wing_tm message
+ *
+ * @return [m] M2 E
+ */
+static inline float mavlink_msg_wing_tm_get_m2_e(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  44);
+}
+
+/**
+ * @brief Decode a wing_tm message into a struct
+ *
+ * @param msg The message to decode
+ * @param wing_tm C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_wing_tm_decode(const mavlink_message_t* msg, mavlink_wing_tm_t* wing_tm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    wing_tm->timestamp = mavlink_msg_wing_tm_get_timestamp(msg);
+    wing_tm->target_lat = mavlink_msg_wing_tm_get_target_lat(msg);
+    wing_tm->target_lon = mavlink_msg_wing_tm_get_target_lon(msg);
+    wing_tm->target_n = mavlink_msg_wing_tm_get_target_n(msg);
+    wing_tm->target_e = mavlink_msg_wing_tm_get_target_e(msg);
+    wing_tm->emc_n = mavlink_msg_wing_tm_get_emc_n(msg);
+    wing_tm->emc_e = mavlink_msg_wing_tm_get_emc_e(msg);
+    wing_tm->m1_n = mavlink_msg_wing_tm_get_m1_n(msg);
+    wing_tm->m1_e = mavlink_msg_wing_tm_get_m1_e(msg);
+    wing_tm->m2_n = mavlink_msg_wing_tm_get_m2_n(msg);
+    wing_tm->m2_e = mavlink_msg_wing_tm_get_m2_e(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_WING_TM_LEN? msg->len : MAVLINK_MSG_ID_WING_TM_LEN;
+        memset(wing_tm, 0, MAVLINK_MSG_ID_WING_TM_LEN);
+    memcpy(wing_tm, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/mavlink_lib/lyra/testsuite.h b/mavlink_lib/lyra/testsuite.h
index cbab659278a022a048662193defc2c0b25d24c1f..fcac05d21ec2ee819550e50f435ce36be06d3f43 100644
--- a/mavlink_lib/lyra/testsuite.h
+++ b/mavlink_lib/lyra/testsuite.h
@@ -3835,13 +3835,14 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_payload_flight_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,205,16
+        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
     };
     mavlink_payload_flight_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.timestamp = packet_in.timestamp;
         packet1.pressure_digi = packet_in.pressure_digi;
         packet1.pressure_static = packet_in.pressure_static;
+        packet1.pressure_dynamic = packet_in.pressure_dynamic;
         packet1.airspeed_pitot = packet_in.airspeed_pitot;
         packet1.altitude_agl = packet_in.altitude_agl;
         packet1.acc_x = packet_in.acc_x;
@@ -3892,12 +3893,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.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.fmm_state , 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.battery_voltage , packet1.cam_battery_voltage , packet1.temperature );
+    mavlink_msg_payload_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dynamic , 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.fmm_state , 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.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.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.fmm_state , 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.battery_voltage , packet1.cam_battery_voltage , packet1.temperature );
+    mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dynamic , 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.fmm_state , 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.battery_voltage , packet1.cam_battery_voltage , packet1.temperature );
     mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -3910,7 +3911,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.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.fmm_state , 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.battery_voltage , packet1.cam_battery_voltage , packet1.temperature );
+    mavlink_msg_payload_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dynamic , 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.fmm_state , 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.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);
 
@@ -4035,10 +4036,11 @@ 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,93372036854777823ULL,93372036854778327ULL,93372036854778831ULL,93372036854779335ULL,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,963505160,963505368,25347,95,162,229,40,107,174,241,52,119,186,253
+        93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,93372036854777823ULL,93372036854778327ULL,93372036854778831ULL,93372036854779335ULL,93372036854779839ULL,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,963505160,963505368,25347,95,162,229,40,107,174,241,52,119,186,253,64
     };
     mavlink_payload_stats_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
+        packet1.timestamp = packet_in.timestamp;
         packet1.liftoff_ts = packet_in.liftoff_ts;
         packet1.liftoff_max_acc_ts = packet_in.liftoff_max_acc_ts;
         packet1.max_speed_ts = packet_in.max_speed_ts;
@@ -4055,12 +4057,10 @@ static void mavlink_test_payload_stats_tm(uint8_t system_id, uint8_t component_i
         packet1.apogee_lon = packet_in.apogee_lon;
         packet1.apogee_alt = packet_in.apogee_alt;
         packet1.apogee_max_acc = packet_in.apogee_max_acc;
-        packet1.wing_emc_n = packet_in.wing_emc_n;
-        packet1.wing_emc_e = packet_in.wing_emc_e;
-        packet1.wing_m1_n = packet_in.wing_m1_n;
-        packet1.wing_m1_e = packet_in.wing_m1_e;
-        packet1.wing_m2_n = packet_in.wing_m2_n;
-        packet1.wing_m2_e = packet_in.wing_m2_e;
+        packet1.wing_target_lat = packet_in.wing_target_lat;
+        packet1.wing_target_lon = packet_in.wing_target_lon;
+        packet1.wing_active_target_n = packet_in.wing_active_target_n;
+        packet1.wing_active_target_e = packet_in.wing_active_target_e;
         packet1.dpl_alt = packet_in.dpl_alt;
         packet1.dpl_max_acc = packet_in.dpl_max_acc;
         packet1.ref_lat = packet_in.ref_lat;
@@ -4071,8 +4071,9 @@ static void mavlink_test_payload_stats_tm(uint8_t system_id, uint8_t component_i
         packet1.free_heap = packet_in.free_heap;
         packet1.log_good = packet_in.log_good;
         packet1.log_number = packet_in.log_number;
+        packet1.wing_algorithm = packet_in.wing_algorithm;
         packet1.nas_state = packet_in.nas_state;
-        packet1.wes_state = packet_in.wes_state;
+        packet1.wnc_state = packet_in.wnc_state;
         packet1.pin_launch = packet_in.pin_launch;
         packet1.pin_nosecone = packet_in.pin_nosecone;
         packet1.cutter_presence = packet_in.cutter_presence;
@@ -4096,12 +4097,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_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.max_speed_ts , packet1.max_speed , packet1.max_speed_altitude , packet1.max_mach_ts , packet1.max_mach , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.apogee_max_acc_ts , packet1.apogee_max_acc , packet1.wing_emc_n , packet1.wing_emc_e , packet1.wing_m1_n , packet1.wing_m1_e , packet1.wing_m2_n , packet1.wing_m2_e , packet1.dpl_ts , packet1.dpl_alt , packet1.dpl_max_acc_ts , packet1.dpl_max_acc , packet1.ref_lat , packet1.ref_lon , packet1.ref_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap , packet1.nas_state , packet1.wes_state , packet1.pin_launch , packet1.pin_nosecone , packet1.cutter_presence , 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_pack(system_id, component_id, &msg , packet1.timestamp , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.max_speed_ts , packet1.max_speed , packet1.max_speed_altitude , packet1.max_mach_ts , packet1.max_mach , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.apogee_max_acc_ts , packet1.apogee_max_acc , packet1.wing_target_lat , packet1.wing_target_lon , packet1.wing_active_target_n , packet1.wing_active_target_e , packet1.wing_algorithm , packet1.dpl_ts , packet1.dpl_alt , packet1.dpl_max_acc_ts , packet1.dpl_max_acc , packet1.ref_lat , packet1.ref_lon , packet1.ref_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap , packet1.nas_state , packet1.wnc_state , packet1.pin_launch , packet1.pin_nosecone , packet1.cutter_presence , 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_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.max_speed_ts , packet1.max_speed , packet1.max_speed_altitude , packet1.max_mach_ts , packet1.max_mach , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.apogee_max_acc_ts , packet1.apogee_max_acc , packet1.wing_emc_n , packet1.wing_emc_e , packet1.wing_m1_n , packet1.wing_m1_e , packet1.wing_m2_n , packet1.wing_m2_e , packet1.dpl_ts , packet1.dpl_alt , packet1.dpl_max_acc_ts , packet1.dpl_max_acc , packet1.ref_lat , packet1.ref_lon , packet1.ref_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap , packet1.nas_state , packet1.wes_state , packet1.pin_launch , packet1.pin_nosecone , packet1.cutter_presence , 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_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.max_speed_ts , packet1.max_speed , packet1.max_speed_altitude , packet1.max_mach_ts , packet1.max_mach , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.apogee_max_acc_ts , packet1.apogee_max_acc , packet1.wing_target_lat , packet1.wing_target_lon , packet1.wing_active_target_n , packet1.wing_active_target_e , packet1.wing_algorithm , packet1.dpl_ts , packet1.dpl_alt , packet1.dpl_max_acc_ts , packet1.dpl_max_acc , packet1.ref_lat , packet1.ref_lon , packet1.ref_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap , packet1.nas_state , packet1.wnc_state , packet1.pin_launch , packet1.pin_nosecone , packet1.cutter_presence , 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);
 
@@ -4114,7 +4115,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_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.max_speed_ts , packet1.max_speed , packet1.max_speed_altitude , packet1.max_mach_ts , packet1.max_mach , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.apogee_max_acc_ts , packet1.apogee_max_acc , packet1.wing_emc_n , packet1.wing_emc_e , packet1.wing_m1_n , packet1.wing_m1_e , packet1.wing_m2_n , packet1.wing_m2_e , packet1.dpl_ts , packet1.dpl_alt , packet1.dpl_max_acc_ts , packet1.dpl_max_acc , packet1.ref_lat , packet1.ref_lon , packet1.ref_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap , packet1.nas_state , packet1.wes_state , packet1.pin_launch , packet1.pin_nosecone , packet1.cutter_presence , 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_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.max_speed_ts , packet1.max_speed , packet1.max_speed_altitude , packet1.max_mach_ts , packet1.max_mach , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.apogee_max_acc_ts , packet1.apogee_max_acc , packet1.wing_target_lat , packet1.wing_target_lon , packet1.wing_active_target_n , packet1.wing_active_target_e , packet1.wing_algorithm , packet1.dpl_ts , packet1.dpl_alt , packet1.dpl_max_acc_ts , packet1.dpl_max_acc , packet1.ref_lat , packet1.ref_lon , packet1.ref_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap , packet1.nas_state , packet1.wnc_state , packet1.pin_launch , packet1.pin_nosecone , packet1.cutter_presence , 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);
 
@@ -4287,7 +4288,7 @@ static void mavlink_test_calibration_tm(uint8_t system_id, uint8_t component_id,
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_calibration_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
+        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
     };
     mavlink_calibration_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -4307,6 +4308,8 @@ static void mavlink_test_calibration_tm(uint8_t system_id, uint8_t component_id,
         packet1.static_press_2_scale = packet_in.static_press_2_scale;
         packet1.dpl_bay_press_bias = packet_in.dpl_bay_press_bias;
         packet1.dpl_bay_press_scale = packet_in.dpl_bay_press_scale;
+        packet1.dynamic_press_bias = packet_in.dynamic_press_bias;
+        packet1.dynamic_press_scale = packet_in.dynamic_press_scale;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -4321,12 +4324,12 @@ static void mavlink_test_calibration_tm(uint8_t system_id, uint8_t component_id,
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_calibration_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.gyro_bias_x , packet1.gyro_bias_y , packet1.gyro_bias_z , packet1.mag_bias_x , packet1.mag_bias_y , packet1.mag_bias_z , packet1.mag_scale_x , packet1.mag_scale_y , packet1.mag_scale_z , packet1.static_press_1_bias , packet1.static_press_1_scale , packet1.static_press_2_bias , packet1.static_press_2_scale , packet1.dpl_bay_press_bias , packet1.dpl_bay_press_scale );
+    mavlink_msg_calibration_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.gyro_bias_x , packet1.gyro_bias_y , packet1.gyro_bias_z , packet1.mag_bias_x , packet1.mag_bias_y , packet1.mag_bias_z , packet1.mag_scale_x , packet1.mag_scale_y , packet1.mag_scale_z , packet1.static_press_1_bias , packet1.static_press_1_scale , packet1.static_press_2_bias , packet1.static_press_2_scale , packet1.dpl_bay_press_bias , packet1.dpl_bay_press_scale , packet1.dynamic_press_bias , packet1.dynamic_press_scale );
     mavlink_msg_calibration_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_calibration_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.gyro_bias_x , packet1.gyro_bias_y , packet1.gyro_bias_z , packet1.mag_bias_x , packet1.mag_bias_y , packet1.mag_bias_z , packet1.mag_scale_x , packet1.mag_scale_y , packet1.mag_scale_z , packet1.static_press_1_bias , packet1.static_press_1_scale , packet1.static_press_2_bias , packet1.static_press_2_scale , packet1.dpl_bay_press_bias , packet1.dpl_bay_press_scale );
+    mavlink_msg_calibration_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.gyro_bias_x , packet1.gyro_bias_y , packet1.gyro_bias_z , packet1.mag_bias_x , packet1.mag_bias_y , packet1.mag_bias_z , packet1.mag_scale_x , packet1.mag_scale_y , packet1.mag_scale_z , packet1.static_press_1_bias , packet1.static_press_1_scale , packet1.static_press_2_bias , packet1.static_press_2_scale , packet1.dpl_bay_press_bias , packet1.dpl_bay_press_scale , packet1.dynamic_press_bias , packet1.dynamic_press_scale );
     mavlink_msg_calibration_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -4339,7 +4342,7 @@ static void mavlink_test_calibration_tm(uint8_t system_id, uint8_t component_id,
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_calibration_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.gyro_bias_x , packet1.gyro_bias_y , packet1.gyro_bias_z , packet1.mag_bias_x , packet1.mag_bias_y , packet1.mag_bias_z , packet1.mag_scale_x , packet1.mag_scale_y , packet1.mag_scale_z , packet1.static_press_1_bias , packet1.static_press_1_scale , packet1.static_press_2_bias , packet1.static_press_2_scale , packet1.dpl_bay_press_bias , packet1.dpl_bay_press_scale );
+    mavlink_msg_calibration_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.gyro_bias_x , packet1.gyro_bias_y , packet1.gyro_bias_z , packet1.mag_bias_x , packet1.mag_bias_y , packet1.mag_bias_z , packet1.mag_scale_x , packet1.mag_scale_y , packet1.mag_scale_z , packet1.static_press_1_bias , packet1.static_press_1_scale , packet1.static_press_2_bias , packet1.static_press_2_scale , packet1.dpl_bay_press_bias , packet1.dpl_bay_press_scale , packet1.dynamic_press_bias , packet1.dynamic_press_scale );
     mavlink_msg_calibration_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
diff --git a/mavlink_lib/lyra/version.h b/mavlink_lib/lyra/version.h
index 55d7020e789fab51bea0846a34be80f93ff8699f..ecf1d27549b88642d137ed8c38167e8bb546fcd4 100644
--- a/mavlink_lib/lyra/version.h
+++ b/mavlink_lib/lyra/version.h
@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Sep 03 2024"
+#define MAVLINK_BUILD_DATE "Mon Sep 09 2024"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 180
  
diff --git a/message_definitions/lyra.xml b/message_definitions/lyra.xml
index 7e58ab113c722d434941022fc18ecc6147d3e55b..71313abb9f4bd64e499b2453f59be67db0bd75e0 100644
--- a/message_definitions/lyra.xml
+++ b/message_definitions/lyra.xml
@@ -733,7 +733,7 @@
             <field name="corrected_pressure" type="float" units="Pa">Corrected pressure</field>
         </message>
         <message id="208" name="ROCKET_FLIGHT_TM">
-            <description>High Rate Telemetry</description>
+            <description>High Rate Rocket Telemetry</description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp in microseconds</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>
@@ -781,10 +781,11 @@
             <field name="temperature" type="float" units="degC">Temperature</field>
         </message>
         <message id="209" name="PAYLOAD_FLIGHT_TM">
-            <description>High Rate Telemetry</description>
+            <description>High Rate Payload Telemetry</description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp in microseconds</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>
+            <field name="pressure_dynamic" type="float" units="Pa">Pressure from dynamic port</field>
             <field name="airspeed_pitot" type="float" units="m/s">Pitot airspeed</field>
             <field name="altitude_agl" type="float" units="m">Altitude above ground level</field>
             <field name="acc_x" type="float" units="m/s^2">Acceleration on X axis (body)</field>
@@ -823,7 +824,7 @@
             <field name="temperature" type="float" units="degC">Temperature</field>
         </message>
         <message id="210" name="ROCKET_STATS_TM">
-            <description>Low Rate Telemetry</description>
+            <description>Low Rate Rocket Telemetry</description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp in microseconds</field>
             <field name="liftoff_ts" type="uint64_t" units="us">System clock at liftoff</field>
             <field name="liftoff_max_acc_ts" type="uint64_t" units="us">System clock at the maximum liftoff acceleration</field>
@@ -871,7 +872,8 @@
             <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>
+            <description>Low Rate Payload Telemetry</description>
+            <field name="timestamp" type="uint64_t" units="us">Timestamp in microseconds</field>
             <field name="liftoff_ts" type="uint64_t" units="us">System clock at liftoff</field>
             <field name="liftoff_max_acc_ts" type="uint64_t" units="us">System clock at the maximum liftoff acceleration</field>
             <field name="liftoff_max_acc" type="float" units="m/s2">Maximum liftoff acceleration</field>
@@ -886,12 +888,11 @@
             <field name="apogee_alt" type="float" units="m">Apogee altitude</field>
             <field name="apogee_max_acc_ts" type="uint64_t" units="us">System clock at max acceleration after apogee</field>
             <field name="apogee_max_acc" type="float" units="m/s2">Max acceleration after apogee</field>
-            <field name="wing_emc_n" type="float" units="m">Wing controller EMC N</field>
-            <field name="wing_emc_e" type="float" units="m">Wing controller EMC E</field>
-            <field name="wing_m1_n" type="float" units="m">Wing controller M1 N</field>
-            <field name="wing_m1_e" type="float" units="m">Wing controller M1 E</field>
-            <field name="wing_m2_n" type="float" units="m">Wing controller M2 N</field>
-            <field name="wing_m2_e" type="float" units="m">Wing controller M2 E</field>
+            <field name="wing_target_lat" type="float" units="deg">Wing target latitude</field>
+            <field name="wing_target_lon" type="float" units="deg">Wing target longitude</field>
+            <field name="wing_active_target_n" type="float" units="m">Wing active target N</field>
+            <field name="wing_active_target_e" type="float" units="m">Wing active target E</field>
+            <field name="wing_algorithm" type="uint8_t">Wing selected algorithm</field>
             <field name="dpl_ts" type="uint64_t" units="us">System clock at main deployment</field>
             <field name="dpl_alt" type="float" units="m">Deployment altitude</field>
             <field name="dpl_max_acc_ts" type="uint64_t" units="us">System clock at max acceleration during main deployment</field>
@@ -903,7 +904,7 @@
             <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="nas_state" type="uint8_t">NAS FSM State</field>
-            <field name="wes_state" type="uint8_t">Wind Estimation System FSM State</field>
+            <field name="wnc_state" type="uint8_t">Wing Controller State</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>
@@ -975,6 +976,8 @@
             <field name="static_press_2_scale" type="float">Static pressure 2 scale</field>
             <field name="dpl_bay_press_bias" type="float" units="Pa">Deployment bay pressure bias</field>
             <field name="dpl_bay_press_scale" type="float">Deployment bay pressure scale</field>
+            <field name="dynamic_press_bias" type="float" units="Pa">Dynamic pressure bias</field>
+            <field name="dynamic_press_scale" type="float">Dynamic pressure scale</field>
         </message>
     </messages>
 </mavlink>