diff --git a/mavlink_lib/gemini/gemini.h b/mavlink_lib/gemini/gemini.h
index ec436e11cf147811813581b11e35d1b8819bcae1..e4cbebc1d11273f505ee675a5fb6238e6ff407a9 100644
--- a/mavlink_lib/gemini/gemini.h
+++ b/mavlink_lib/gemini/gemini.h
@@ -11,7 +11,7 @@
 #endif
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -7592676323702278911
+#define MAVLINK_THIS_XML_HASH 737153578550328602
 
 #ifdef __cplusplus
 extern "C" {
@@ -20,11 +20,11 @@ extern "C" {
 // MESSAGE LENGTHS AND CRCS
 
 #ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 44, 32, 32, 32, 32, 56, 21, 5, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 46, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 46, 28, 27, 53, 77, 0, 171, 162, 92, 76, 42, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 44, 32, 32, 32, 32, 56, 21, 5, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 46, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 46, 28, 27, 53, 77, 0, 171, 158, 92, 76, 42, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #endif
 
 #ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 57, 72, 87, 223, 245, 212, 140, 148, 6, 155, 87, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 104, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 242, 142, 108, 133, 234, 66, 0, 141, 6, 245, 115, 89, 241, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 57, 72, 87, 223, 245, 212, 140, 148, 6, 155, 87, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 104, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 242, 142, 108, 133, 234, 66, 0, 141, 229, 245, 115, 89, 241, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #endif
 
 #include "../protocol.h"
@@ -107,7 +107,7 @@ typedef enum MavCommandList
    MAV_CMD_FORCE_LANDING=6, /* Command to communicate the end of the mission and close the file descriptors in the SD card | */
    MAV_CMD_FORCE_APOGEE=7, /* Command to trigger the apogee event | */
    MAV_CMD_FORCE_EXPULSION=8, /* Command to open the nosecone | */
-   MAV_CMD_FORCE_MAIN=9, /* Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially | */
+   MAV_CMD_FORCE_DEPLOYMENT=9, /* Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially | */
    MAV_CMD_START_LOGGING=10, /* Command to enable sensor logging | */
    MAV_CMD_STOP_LOGGING=11, /* Command to permanently close the log file | */
    MAV_CMD_FORCE_REBOOT=12, /* Command to reset the board from test status | */
@@ -215,7 +215,7 @@ typedef enum PinsList
 
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -7592676323702278911
+#define MAVLINK_THIS_XML_HASH 737153578550328602
 
 #if MAVLINK_THIS_XML_HASH == MAVLINK_PRIMARY_XML_HASH
 # define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_RECEIVER_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_FSM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
diff --git a/mavlink_lib/gemini/mavlink.h b/mavlink_lib/gemini/mavlink.h
index de596de49f101649f496cd966a56331b950f5c93..70b2c261d7bb1ca0d9c24c85dbc6d594e20ba852 100644
--- a/mavlink_lib/gemini/mavlink.h
+++ b/mavlink_lib/gemini/mavlink.h
@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -7592676323702278911
+#define MAVLINK_PRIMARY_XML_HASH 737153578550328602
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 254
diff --git a/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h b/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h
index ce9f5192d70b7d06eff94a7af31a979090aecfb8..f68e04122267929b30941d865e5f6860c9bef31a 100644
--- a/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h
+++ b/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h
@@ -8,7 +8,6 @@ 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_dpl; /*< [Pa] Pressure from deployment vane sensor*/
  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)*/
@@ -51,13 +50,13 @@ typedef struct __mavlink_payload_flight_tm_t {
  int8_t logger_error; /*<  Logger error (0 = no error)*/
 } mavlink_payload_flight_tm_t;
 
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN 162
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN 162
-#define MAVLINK_MSG_ID_209_LEN 162
-#define MAVLINK_MSG_ID_209_MIN_LEN 162
+#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_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 6
-#define MAVLINK_MSG_ID_209_CRC 6
+#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC 229
+#define MAVLINK_MSG_ID_209_CRC 229
 
 
 
@@ -65,101 +64,99 @@ typedef struct __mavlink_payload_flight_tm_t {
 #define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \
     209, \
     "PAYLOAD_FLIGHT_TM", \
-    44, \
+    43, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
-         { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \
+         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 152, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
+         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 153, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
+         { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 154, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \
          { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \
          { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \
-         { "pressure_dpl", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, pressure_dpl) }, \
-         { "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, 159, 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) }, \
-         { "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) }, \
-         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
-         { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, vbat) }, \
-         { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, vsupply_5v) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
-         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
+         { "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, 155, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
+         { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
+         { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
+         { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
+         { "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) }, \
+         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
+         { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, vbat) }, \
+         { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, vsupply_5v) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
+         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \
     "PAYLOAD_FLIGHT_TM", \
-    44, \
+    43, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
-         { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \
+         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 152, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
+         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 153, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
+         { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 154, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \
          { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \
          { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \
-         { "pressure_dpl", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, pressure_dpl) }, \
-         { "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, 159, 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) }, \
-         { "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) }, \
-         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
-         { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, vbat) }, \
-         { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, vsupply_5v) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
-         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
+         { "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, 155, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
+         { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
+         { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
+         { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
+         { "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) }, \
+         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
+         { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, vbat) }, \
+         { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, vsupply_5v) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
+         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
          } \
 }
 #endif
@@ -176,7 +173,6 @@ typedef struct __mavlink_payload_flight_tm_t {
  * @param wes_state  Wind Estimation System FSM State
  * @param pressure_digi [Pa] Pressure from digital sensor
  * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
  * @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)
@@ -217,54 +213,53 @@ 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, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float vbat, float vsupply_5v, float temperature, int8_t logger_error)
+                               uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float vbat, float vsupply_5v, float temperature, int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
     _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, pressure_dpl);
-    _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, vbat);
-    _mav_put_float(buf, 148, vsupply_5v);
-    _mav_put_float(buf, 152, temperature);
-    _mav_put_uint8_t(buf, 156, fmm_state);
-    _mav_put_uint8_t(buf, 157, nas_state);
-    _mav_put_uint8_t(buf, 158, wes_state);
-    _mav_put_uint8_t(buf, 159, gps_fix);
-    _mav_put_uint8_t(buf, 160, pin_nosecone);
-    _mav_put_int8_t(buf, 161, logger_error);
+    _mav_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, vbat);
+    _mav_put_float(buf, 144, vsupply_5v);
+    _mav_put_float(buf, 148, temperature);
+    _mav_put_uint8_t(buf, 152, fmm_state);
+    _mav_put_uint8_t(buf, 153, nas_state);
+    _mav_put_uint8_t(buf, 154, wes_state);
+    _mav_put_uint8_t(buf, 155, gps_fix);
+    _mav_put_uint8_t(buf, 156, pin_nosecone);
+    _mav_put_int8_t(buf, 157, logger_error);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
 #else
@@ -272,7 +267,6 @@ 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_dpl = pressure_dpl;
     packet.airspeed_pitot = airspeed_pitot;
     packet.altitude_agl = altitude_agl;
     packet.acc_x = acc_x;
@@ -333,7 +327,6 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
  * @param wes_state  Wind Estimation System FSM State
  * @param pressure_digi [Pa] Pressure from digital sensor
  * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
  * @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)
@@ -375,54 +368,53 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin
  */
 static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,uint8_t fmm_state,uint8_t nas_state,uint8_t wes_state,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float left_servo_angle,float right_servo_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float wes_n,float wes_e,uint8_t pin_nosecone,float vbat,float vsupply_5v,float temperature,int8_t logger_error)
+                                   uint64_t timestamp,uint8_t fmm_state,uint8_t nas_state,uint8_t wes_state,float pressure_digi,float pressure_static,float airspeed_pitot,float altitude_agl,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float left_servo_angle,float right_servo_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float wes_n,float wes_e,uint8_t pin_nosecone,float vbat,float vsupply_5v,float temperature,int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
     _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, pressure_dpl);
-    _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, vbat);
-    _mav_put_float(buf, 148, vsupply_5v);
-    _mav_put_float(buf, 152, temperature);
-    _mav_put_uint8_t(buf, 156, fmm_state);
-    _mav_put_uint8_t(buf, 157, nas_state);
-    _mav_put_uint8_t(buf, 158, wes_state);
-    _mav_put_uint8_t(buf, 159, gps_fix);
-    _mav_put_uint8_t(buf, 160, pin_nosecone);
-    _mav_put_int8_t(buf, 161, logger_error);
+    _mav_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, vbat);
+    _mav_put_float(buf, 144, vsupply_5v);
+    _mav_put_float(buf, 148, temperature);
+    _mav_put_uint8_t(buf, 152, fmm_state);
+    _mav_put_uint8_t(buf, 153, nas_state);
+    _mav_put_uint8_t(buf, 154, wes_state);
+    _mav_put_uint8_t(buf, 155, gps_fix);
+    _mav_put_uint8_t(buf, 156, pin_nosecone);
+    _mav_put_int8_t(buf, 157, logger_error);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
 #else
@@ -430,7 +422,6 @@ 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_dpl = pressure_dpl;
     packet.airspeed_pitot = airspeed_pitot;
     packet.altitude_agl = altitude_agl;
     packet.acc_x = acc_x;
@@ -489,7 +480,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id
  */
 static inline uint16_t mavlink_msg_payload_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm)
 {
-    return mavlink_msg_payload_flight_tm_pack(system_id, component_id, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->pressure_dpl, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->vbat, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error);
+    return mavlink_msg_payload_flight_tm_pack(system_id, component_id, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->vbat, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error);
 }
 
 /**
@@ -503,7 +494,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_encode(uint8_t system_id, u
  */
 static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm)
 {
-    return mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, chan, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->pressure_dpl, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->vbat, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error);
+    return mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, chan, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->vbat, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error);
 }
 
 /**
@@ -516,7 +507,6 @@ static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_
  * @param wes_state  Wind Estimation System FSM State
  * @param pressure_digi [Pa] Pressure from digital sensor
  * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
  * @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)
@@ -557,54 +547,53 @@ 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, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float vbat, float vsupply_5v, float temperature, int8_t logger_error)
+static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float vbat, float vsupply_5v, float temperature, int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
     _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, pressure_dpl);
-    _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, vbat);
-    _mav_put_float(buf, 148, vsupply_5v);
-    _mav_put_float(buf, 152, temperature);
-    _mav_put_uint8_t(buf, 156, fmm_state);
-    _mav_put_uint8_t(buf, 157, nas_state);
-    _mav_put_uint8_t(buf, 158, wes_state);
-    _mav_put_uint8_t(buf, 159, gps_fix);
-    _mav_put_uint8_t(buf, 160, pin_nosecone);
-    _mav_put_int8_t(buf, 161, logger_error);
+    _mav_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, vbat);
+    _mav_put_float(buf, 144, vsupply_5v);
+    _mav_put_float(buf, 148, temperature);
+    _mav_put_uint8_t(buf, 152, fmm_state);
+    _mav_put_uint8_t(buf, 153, nas_state);
+    _mav_put_uint8_t(buf, 154, wes_state);
+    _mav_put_uint8_t(buf, 155, gps_fix);
+    _mav_put_uint8_t(buf, 156, pin_nosecone);
+    _mav_put_int8_t(buf, 157, logger_error);
 
     _mav_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
@@ -612,7 +601,6 @@ 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_dpl = pressure_dpl;
     packet.airspeed_pitot = airspeed_pitot;
     packet.altitude_agl = altitude_agl;
     packet.acc_x = acc_x;
@@ -666,7 +654,7 @@ static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, ui
 static inline void mavlink_msg_payload_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_payload_flight_tm_t* payload_flight_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_payload_flight_tm_send(chan, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->pressure_dpl, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->vbat, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error);
+    mavlink_msg_payload_flight_tm_send(chan, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->vbat, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)payload_flight_tm, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
 #endif
@@ -680,54 +668,53 @@ static inline void mavlink_msg_payload_flight_tm_send_struct(mavlink_channel_t c
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float vbat, float vsupply_5v, float temperature, int8_t logger_error)
+static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float vbat, float vsupply_5v, float temperature, int8_t logger_error)
 {
 #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, pressure_dpl);
-    _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, vbat);
-    _mav_put_float(buf, 148, vsupply_5v);
-    _mav_put_float(buf, 152, temperature);
-    _mav_put_uint8_t(buf, 156, fmm_state);
-    _mav_put_uint8_t(buf, 157, nas_state);
-    _mav_put_uint8_t(buf, 158, wes_state);
-    _mav_put_uint8_t(buf, 159, gps_fix);
-    _mav_put_uint8_t(buf, 160, pin_nosecone);
-    _mav_put_int8_t(buf, 161, logger_error);
+    _mav_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, vbat);
+    _mav_put_float(buf, 144, vsupply_5v);
+    _mav_put_float(buf, 148, temperature);
+    _mav_put_uint8_t(buf, 152, fmm_state);
+    _mav_put_uint8_t(buf, 153, nas_state);
+    _mav_put_uint8_t(buf, 154, wes_state);
+    _mav_put_uint8_t(buf, 155, gps_fix);
+    _mav_put_uint8_t(buf, 156, pin_nosecone);
+    _mav_put_int8_t(buf, 157, logger_error);
 
     _mav_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
@@ -735,7 +722,6 @@ 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_dpl = pressure_dpl;
     packet->airspeed_pitot = airspeed_pitot;
     packet->altitude_agl = altitude_agl;
     packet->acc_x = acc_x;
@@ -804,7 +790,7 @@ static inline uint64_t mavlink_msg_payload_flight_tm_get_timestamp(const mavlink
  */
 static inline uint8_t mavlink_msg_payload_flight_tm_get_fmm_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  156);
+    return _MAV_RETURN_uint8_t(msg,  152);
 }
 
 /**
@@ -814,7 +800,7 @@ static inline uint8_t mavlink_msg_payload_flight_tm_get_fmm_state(const mavlink_
  */
 static inline uint8_t mavlink_msg_payload_flight_tm_get_nas_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  157);
+    return _MAV_RETURN_uint8_t(msg,  153);
 }
 
 /**
@@ -824,7 +810,7 @@ static inline uint8_t mavlink_msg_payload_flight_tm_get_nas_state(const mavlink_
  */
 static inline uint8_t mavlink_msg_payload_flight_tm_get_wes_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  158);
+    return _MAV_RETURN_uint8_t(msg,  154);
 }
 
 /**
@@ -847,16 +833,6 @@ static inline float mavlink_msg_payload_flight_tm_get_pressure_static(const mavl
     return _MAV_RETURN_float(msg,  12);
 }
 
-/**
- * @brief Get field pressure_dpl from payload_flight_tm message
- *
- * @return [Pa] Pressure from deployment vane sensor
- */
-static inline float mavlink_msg_payload_flight_tm_get_pressure_dpl(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_float(msg,  16);
-}
-
 /**
  * @brief Get field airspeed_pitot from payload_flight_tm message
  *
@@ -864,7 +840,7 @@ static inline float mavlink_msg_payload_flight_tm_get_pressure_dpl(const mavlink
  */
 static inline float mavlink_msg_payload_flight_tm_get_airspeed_pitot(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  20);
+    return _MAV_RETURN_float(msg,  16);
 }
 
 /**
@@ -874,7 +850,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,  24);
+    return _MAV_RETURN_float(msg,  20);
 }
 
 /**
@@ -884,7 +860,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,  28);
+    return _MAV_RETURN_float(msg,  24);
 }
 
 /**
@@ -894,7 +870,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,  32);
+    return _MAV_RETURN_float(msg,  28);
 }
 
 /**
@@ -904,7 +880,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,  36);
+    return _MAV_RETURN_float(msg,  32);
 }
 
 /**
@@ -914,7 +890,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,  40);
+    return _MAV_RETURN_float(msg,  36);
 }
 
 /**
@@ -924,7 +900,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,  44);
+    return _MAV_RETURN_float(msg,  40);
 }
 
 /**
@@ -934,7 +910,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,  48);
+    return _MAV_RETURN_float(msg,  44);
 }
 
 /**
@@ -944,7 +920,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,  52);
+    return _MAV_RETURN_float(msg,  48);
 }
 
 /**
@@ -954,7 +930,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,  56);
+    return _MAV_RETURN_float(msg,  52);
 }
 
 /**
@@ -964,7 +940,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,  60);
+    return _MAV_RETURN_float(msg,  56);
 }
 
 /**
@@ -974,7 +950,7 @@ static inline float mavlink_msg_payload_flight_tm_get_mag_z(const mavlink_messag
  */
 static inline uint8_t mavlink_msg_payload_flight_tm_get_gps_fix(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  159);
+    return _MAV_RETURN_uint8_t(msg,  155);
 }
 
 /**
@@ -984,7 +960,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,  64);
+    return _MAV_RETURN_float(msg,  60);
 }
 
 /**
@@ -994,7 +970,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,  68);
+    return _MAV_RETURN_float(msg,  64);
 }
 
 /**
@@ -1004,7 +980,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,  72);
+    return _MAV_RETURN_float(msg,  68);
 }
 
 /**
@@ -1014,7 +990,7 @@ static inline float mavlink_msg_payload_flight_tm_get_gps_alt(const mavlink_mess
  */
 static inline float mavlink_msg_payload_flight_tm_get_left_servo_angle(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  76);
+    return _MAV_RETURN_float(msg,  72);
 }
 
 /**
@@ -1024,7 +1000,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,  80);
+    return _MAV_RETURN_float(msg,  76);
 }
 
 /**
@@ -1034,7 +1010,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,  84);
+    return _MAV_RETURN_float(msg,  80);
 }
 
 /**
@@ -1044,7 +1020,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,  88);
+    return _MAV_RETURN_float(msg,  84);
 }
 
 /**
@@ -1054,7 +1030,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,  92);
+    return _MAV_RETURN_float(msg,  88);
 }
 
 /**
@@ -1064,7 +1040,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,  96);
+    return _MAV_RETURN_float(msg,  92);
 }
 
 /**
@@ -1074,7 +1050,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,  100);
+    return _MAV_RETURN_float(msg,  96);
 }
 
 /**
@@ -1084,7 +1060,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,  104);
+    return _MAV_RETURN_float(msg,  100);
 }
 
 /**
@@ -1094,7 +1070,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,  108);
+    return _MAV_RETURN_float(msg,  104);
 }
 
 /**
@@ -1104,7 +1080,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,  112);
+    return _MAV_RETURN_float(msg,  108);
 }
 
 /**
@@ -1114,7 +1090,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,  116);
+    return _MAV_RETURN_float(msg,  112);
 }
 
 /**
@@ -1124,7 +1100,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,  120);
+    return _MAV_RETURN_float(msg,  116);
 }
 
 /**
@@ -1134,7 +1110,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,  124);
+    return _MAV_RETURN_float(msg,  120);
 }
 
 /**
@@ -1144,7 +1120,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,  128);
+    return _MAV_RETURN_float(msg,  124);
 }
 
 /**
@@ -1154,7 +1130,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,  132);
+    return _MAV_RETURN_float(msg,  128);
 }
 
 /**
@@ -1164,7 +1140,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,  136);
+    return _MAV_RETURN_float(msg,  132);
 }
 
 /**
@@ -1174,7 +1150,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,  140);
+    return _MAV_RETURN_float(msg,  136);
 }
 
 /**
@@ -1184,7 +1160,7 @@ static inline float mavlink_msg_payload_flight_tm_get_wes_e(const mavlink_messag
  */
 static inline uint8_t mavlink_msg_payload_flight_tm_get_pin_nosecone(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  160);
+    return _MAV_RETURN_uint8_t(msg,  156);
 }
 
 /**
@@ -1194,7 +1170,7 @@ static inline uint8_t mavlink_msg_payload_flight_tm_get_pin_nosecone(const mavli
  */
 static inline float mavlink_msg_payload_flight_tm_get_vbat(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  144);
+    return _MAV_RETURN_float(msg,  140);
 }
 
 /**
@@ -1204,7 +1180,7 @@ static inline float mavlink_msg_payload_flight_tm_get_vbat(const mavlink_message
  */
 static inline float mavlink_msg_payload_flight_tm_get_vsupply_5v(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  148);
+    return _MAV_RETURN_float(msg,  144);
 }
 
 /**
@@ -1214,7 +1190,7 @@ static inline float mavlink_msg_payload_flight_tm_get_vsupply_5v(const mavlink_m
  */
 static inline float mavlink_msg_payload_flight_tm_get_temperature(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  152);
+    return _MAV_RETURN_float(msg,  148);
 }
 
 /**
@@ -1224,7 +1200,7 @@ static inline float mavlink_msg_payload_flight_tm_get_temperature(const mavlink_
  */
 static inline int8_t mavlink_msg_payload_flight_tm_get_logger_error(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_int8_t(msg,  161);
+    return _MAV_RETURN_int8_t(msg,  157);
 }
 
 /**
@@ -1239,7 +1215,6 @@ 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_dpl = mavlink_msg_payload_flight_tm_get_pressure_dpl(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/gemini/mavlink_msg_set_servo_angle_tc.h b/mavlink_lib/gemini/mavlink_msg_set_servo_angle_tc.h
index a9e3fa6e354c97e420ba4a778f8e11dc9c9c0848..74f2888721a7ed79d479df991d640deb064d50cc 100644
--- a/mavlink_lib/gemini/mavlink_msg_set_servo_angle_tc.h
+++ b/mavlink_lib/gemini/mavlink_msg_set_servo_angle_tc.h
@@ -5,7 +5,7 @@
 
 
 typedef struct __mavlink_set_servo_angle_tc_t {
- float angle; /*< [deg] Servo angle*/
+ float angle; /*<  Servo angle in normalized value [0-1]*/
  uint8_t servo_id; /*<  A member of the ServosList enum*/
 } mavlink_set_servo_angle_tc_t;
 
@@ -45,7 +45,7 @@ typedef struct __mavlink_set_servo_angle_tc_t {
  * @param msg The MAVLink message to compress the data into
  *
  * @param servo_id  A member of the ServosList enum
- * @param angle [deg] Servo angle
+ * @param angle  Servo angle in normalized value [0-1]
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_set_servo_angle_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_set_servo_angle_tc_pack(uint8_t system_id, ui
  * @param chan The MAVLink channel this message will be sent over
  * @param msg The MAVLink message to compress the data into
  * @param servo_id  A member of the ServosList enum
- * @param angle [deg] Servo angle
+ * @param angle  Servo angle in normalized value [0-1]
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_set_servo_angle_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -133,7 +133,7 @@ static inline uint16_t mavlink_msg_set_servo_angle_tc_encode_chan(uint8_t system
  * @param chan MAVLink channel to send the message
  *
  * @param servo_id  A member of the ServosList enum
- * @param angle [deg] Servo angle
+ * @param angle  Servo angle in normalized value [0-1]
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
@@ -212,7 +212,7 @@ static inline uint8_t mavlink_msg_set_servo_angle_tc_get_servo_id(const mavlink_
 /**
  * @brief Get field angle from set_servo_angle_tc message
  *
- * @return [deg] Servo angle
+ * @return  Servo angle in normalized value [0-1]
  */
 static inline float mavlink_msg_set_servo_angle_tc_get_angle(const mavlink_message_t* msg)
 {
diff --git a/mavlink_lib/gemini/testsuite.h b/mavlink_lib/gemini/testsuite.h
index a4672adc00c0fa7ffd6e5be1dc926d4a835867cf..1e8930dd99b1ae3a60bd73487f544cde99bb5df1 100644
--- a/mavlink_lib/gemini/testsuite.h
+++ b/mavlink_lib/gemini/testsuite.h
@@ -2775,14 +2775,13 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_payload_flight_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,217,28,95,162,229,40
+        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,205,16,83,150,217,28
     };
     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_dpl = packet_in.pressure_dpl;
         packet1.airspeed_pitot = packet_in.airspeed_pitot;
         packet1.altitude_agl = packet_in.altitude_agl;
         packet1.acc_x = packet_in.acc_x;
@@ -2837,12 +2836,12 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_payload_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.logger_error );
+    mavlink_msg_payload_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.logger_error );
     mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.logger_error );
+    mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.logger_error );
     mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2855,7 +2854,7 @@ static void mavlink_test_payload_flight_tm(uint8_t system_id, uint8_t component_
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_payload_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.logger_error );
+    mavlink_msg_payload_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.logger_error );
     mavlink_msg_payload_flight_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
diff --git a/mavlink_lib/gemini/version.h b/mavlink_lib/gemini/version.h
index a51fbcded49218b215fdc3b34ef14dc8c4bd0b5a..77b842b6e781a9d2d2910a33f1610ab127ad45d7 100644
--- a/mavlink_lib/gemini/version.h
+++ b/mavlink_lib/gemini/version.h
@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Fri Aug 04 2023"
+#define MAVLINK_BUILD_DATE "Sat Aug 05 2023"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 171
  
diff --git a/message_definitions/gemini.xml b/message_definitions/gemini.xml
index a192e5b4c7e2bb6f7775fc1af459e76c3ca5420a..a589356ccf86a67b88c9089e3ea129d788981eac 100644
--- a/message_definitions/gemini.xml
+++ b/message_definitions/gemini.xml
@@ -163,7 +163,7 @@
             <entry name="MAV_CMD_FORCE_EXPULSION" value="8">
                 <description>Command to open the nosecone</description>
             </entry>
-            <entry name="MAV_CMD_FORCE_MAIN" value="9">
+            <entry name="MAV_CMD_FORCE_DEPLOYMENT" value="9">
                 <description>Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially</description>
             </entry>
             <entry name="MAV_CMD_START_LOGGING" value="10">
@@ -233,7 +233,7 @@
         <message id="6" name="SET_SERVO_ANGLE_TC">
             <description>Sets the angle of a certain servo</description>
             <field name="servo_id" type="uint8_t">A member of the ServosList enum</field>
-            <field name="angle" type="float" units="deg">Servo angle</field>
+            <field name="angle" type="float">Servo angle in normalized value [0-1]</field>
         </message>
         <message id="7" name="WIGGLE_SERVO_TC">
             <description>Wiggles the specified servo</description>
@@ -599,7 +599,6 @@
             <field name="wes_state" type="uint8_t">Wind Estimation System FSM State</field>
             <field name="pressure_digi" type="float" units="Pa">Pressure from digital sensor</field>
             <field name="pressure_static" type="float" units="Pa">Pressure from static port</field>
-            <field name="pressure_dpl" type="float" units="Pa">Pressure from deployment vane sensor</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>