diff --git a/mavlink_lib/pyxis/mavlink.h b/mavlink_lib/pyxis/mavlink.h
index 32692825708d6ac94f8d9be56389c99829495a82..a441330a9c196314f91c64e8eca3f11054c4fc83 100644
--- a/mavlink_lib/pyxis/mavlink.h
+++ b/mavlink_lib/pyxis/mavlink.h
@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -1786394334196858732
+#define MAVLINK_PRIMARY_XML_HASH -7023161531361269467
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 254
diff --git a/mavlink_lib/pyxis/mavlink_msg_ada_tm.h b/mavlink_lib/pyxis/mavlink_msg_ada_tm.h
index 5291aad038e7ca063da8377c19de46f021846d49..f96a75c0db6fcd54bea1d9bb6658860e7e998179 100644
--- a/mavlink_lib/pyxis/mavlink_msg_ada_tm.h
+++ b/mavlink_lib/pyxis/mavlink_msg_ada_tm.h
@@ -16,16 +16,17 @@ typedef struct __mavlink_ada_tm_t {
  float ref_temperature; /*< [degC] Calibration temperature*/
  float msl_pressure; /*< [Pa] Expected pressure at mean sea level*/
  float msl_temperature; /*< [degC] Expected temperature at mean sea level*/
+ float dpl_altitude; /*< [m] Main parachute deployment altituyde*/
  uint8_t state; /*<  ADA current state*/
 } mavlink_ada_tm_t;
 
-#define MAVLINK_MSG_ID_ADA_TM_LEN 49
-#define MAVLINK_MSG_ID_ADA_TM_MIN_LEN 49
-#define MAVLINK_MSG_ID_205_LEN 49
-#define MAVLINK_MSG_ID_205_MIN_LEN 49
+#define MAVLINK_MSG_ID_ADA_TM_LEN 53
+#define MAVLINK_MSG_ID_ADA_TM_MIN_LEN 53
+#define MAVLINK_MSG_ID_205_LEN 53
+#define MAVLINK_MSG_ID_205_MIN_LEN 53
 
-#define MAVLINK_MSG_ID_ADA_TM_CRC 79
-#define MAVLINK_MSG_ID_205_CRC 79
+#define MAVLINK_MSG_ID_ADA_TM_CRC 234
+#define MAVLINK_MSG_ID_205_CRC 234
 
 
 
@@ -33,9 +34,9 @@ typedef struct __mavlink_ada_tm_t {
 #define MAVLINK_MESSAGE_INFO_ADA_TM { \
     205, \
     "ADA_TM", \
-    12, \
+    13, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ada_tm_t, timestamp) }, \
-         { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_ada_tm_t, state) }, \
+         { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_ada_tm_t, state) }, \
          { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ada_tm_t, kalman_x0) }, \
          { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ada_tm_t, kalman_x1) }, \
          { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ada_tm_t, kalman_x2) }, \
@@ -46,14 +47,15 @@ typedef struct __mavlink_ada_tm_t {
          { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ada_tm_t, ref_temperature) }, \
          { "msl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ada_tm_t, msl_pressure) }, \
          { "msl_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ada_tm_t, msl_temperature) }, \
+         { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ada_tm_t, dpl_altitude) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_ADA_TM { \
     "ADA_TM", \
-    12, \
+    13, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ada_tm_t, timestamp) }, \
-         { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_ada_tm_t, state) }, \
+         { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_ada_tm_t, state) }, \
          { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ada_tm_t, kalman_x0) }, \
          { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ada_tm_t, kalman_x1) }, \
          { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ada_tm_t, kalman_x2) }, \
@@ -64,6 +66,7 @@ typedef struct __mavlink_ada_tm_t {
          { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ada_tm_t, ref_temperature) }, \
          { "msl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ada_tm_t, msl_pressure) }, \
          { "msl_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ada_tm_t, msl_temperature) }, \
+         { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ada_tm_t, dpl_altitude) }, \
          } \
 }
 #endif
@@ -86,10 +89,11 @@ typedef struct __mavlink_ada_tm_t {
  * @param ref_temperature [degC] Calibration temperature
  * @param msl_pressure [Pa] Expected pressure at mean sea level
  * @param msl_temperature [degC] Expected temperature at mean sea level
+ * @param dpl_altitude [m] Main parachute deployment altituyde
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_ada_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature)
+                               uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
@@ -104,7 +108,8 @@ static inline uint16_t mavlink_msg_ada_tm_pack(uint8_t system_id, uint8_t compon
     _mav_put_float(buf, 36, ref_temperature);
     _mav_put_float(buf, 40, msl_pressure);
     _mav_put_float(buf, 44, msl_temperature);
-    _mav_put_uint8_t(buf, 48, state);
+    _mav_put_float(buf, 48, dpl_altitude);
+    _mav_put_uint8_t(buf, 52, state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
 #else
@@ -120,6 +125,7 @@ static inline uint16_t mavlink_msg_ada_tm_pack(uint8_t system_id, uint8_t compon
     packet.ref_temperature = ref_temperature;
     packet.msl_pressure = msl_pressure;
     packet.msl_temperature = msl_temperature;
+    packet.dpl_altitude = dpl_altitude;
     packet.state = state;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
@@ -147,11 +153,12 @@ static inline uint16_t mavlink_msg_ada_tm_pack(uint8_t system_id, uint8_t compon
  * @param ref_temperature [degC] Calibration temperature
  * @param msl_pressure [Pa] Expected pressure at mean sea level
  * @param msl_temperature [degC] Expected temperature at mean sea level
+ * @param dpl_altitude [m] Main parachute deployment altituyde
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_ada_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,uint8_t state,float kalman_x0,float kalman_x1,float kalman_x2,float vertical_speed,float msl_altitude,float ref_pressure,float ref_altitude,float ref_temperature,float msl_pressure,float msl_temperature)
+                                   uint64_t timestamp,uint8_t state,float kalman_x0,float kalman_x1,float kalman_x2,float vertical_speed,float msl_altitude,float ref_pressure,float ref_altitude,float ref_temperature,float msl_pressure,float msl_temperature,float dpl_altitude)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
@@ -166,7 +173,8 @@ static inline uint16_t mavlink_msg_ada_tm_pack_chan(uint8_t system_id, uint8_t c
     _mav_put_float(buf, 36, ref_temperature);
     _mav_put_float(buf, 40, msl_pressure);
     _mav_put_float(buf, 44, msl_temperature);
-    _mav_put_uint8_t(buf, 48, state);
+    _mav_put_float(buf, 48, dpl_altitude);
+    _mav_put_uint8_t(buf, 52, state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
 #else
@@ -182,6 +190,7 @@ static inline uint16_t mavlink_msg_ada_tm_pack_chan(uint8_t system_id, uint8_t c
     packet.ref_temperature = ref_temperature;
     packet.msl_pressure = msl_pressure;
     packet.msl_temperature = msl_temperature;
+    packet.dpl_altitude = dpl_altitude;
     packet.state = state;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
@@ -201,7 +210,7 @@ static inline uint16_t mavlink_msg_ada_tm_pack_chan(uint8_t system_id, uint8_t c
  */
 static inline uint16_t mavlink_msg_ada_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
 {
-    return mavlink_msg_ada_tm_pack(system_id, component_id, msg, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature);
+    return mavlink_msg_ada_tm_pack(system_id, component_id, msg, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
 }
 
 /**
@@ -215,7 +224,7 @@ static inline uint16_t mavlink_msg_ada_tm_encode(uint8_t system_id, uint8_t comp
  */
 static inline uint16_t mavlink_msg_ada_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
 {
-    return mavlink_msg_ada_tm_pack_chan(system_id, component_id, chan, msg, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature);
+    return mavlink_msg_ada_tm_pack_chan(system_id, component_id, chan, msg, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
 }
 
 /**
@@ -234,10 +243,11 @@ static inline uint16_t mavlink_msg_ada_tm_encode_chan(uint8_t system_id, uint8_t
  * @param ref_temperature [degC] Calibration temperature
  * @param msl_pressure [Pa] Expected pressure at mean sea level
  * @param msl_temperature [degC] Expected temperature at mean sea level
+ * @param dpl_altitude [m] Main parachute deployment altituyde
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_ada_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature)
+static inline void mavlink_msg_ada_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
@@ -252,7 +262,8 @@ static inline void mavlink_msg_ada_tm_send(mavlink_channel_t chan, uint64_t time
     _mav_put_float(buf, 36, ref_temperature);
     _mav_put_float(buf, 40, msl_pressure);
     _mav_put_float(buf, 44, msl_temperature);
-    _mav_put_uint8_t(buf, 48, state);
+    _mav_put_float(buf, 48, dpl_altitude);
+    _mav_put_uint8_t(buf, 52, state);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, buf, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
 #else
@@ -268,6 +279,7 @@ static inline void mavlink_msg_ada_tm_send(mavlink_channel_t chan, uint64_t time
     packet.ref_temperature = ref_temperature;
     packet.msl_pressure = msl_pressure;
     packet.msl_temperature = msl_temperature;
+    packet.dpl_altitude = dpl_altitude;
     packet.state = state;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)&packet, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
@@ -282,7 +294,7 @@ static inline void mavlink_msg_ada_tm_send(mavlink_channel_t chan, uint64_t time
 static inline void mavlink_msg_ada_tm_send_struct(mavlink_channel_t chan, const mavlink_ada_tm_t* ada_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_ada_tm_send(chan, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature);
+    mavlink_msg_ada_tm_send(chan, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)ada_tm, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
 #endif
@@ -296,7 +308,7 @@ static inline void mavlink_msg_ada_tm_send_struct(mavlink_channel_t chan, const
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_ada_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature)
+static inline void mavlink_msg_ada_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -311,7 +323,8 @@ static inline void mavlink_msg_ada_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     _mav_put_float(buf, 36, ref_temperature);
     _mav_put_float(buf, 40, msl_pressure);
     _mav_put_float(buf, 44, msl_temperature);
-    _mav_put_uint8_t(buf, 48, state);
+    _mav_put_float(buf, 48, dpl_altitude);
+    _mav_put_uint8_t(buf, 52, state);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, buf, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
 #else
@@ -327,6 +340,7 @@ static inline void mavlink_msg_ada_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     packet->ref_temperature = ref_temperature;
     packet->msl_pressure = msl_pressure;
     packet->msl_temperature = msl_temperature;
+    packet->dpl_altitude = dpl_altitude;
     packet->state = state;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)packet, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
@@ -356,7 +370,7 @@ static inline uint64_t mavlink_msg_ada_tm_get_timestamp(const mavlink_message_t*
  */
 static inline uint8_t mavlink_msg_ada_tm_get_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  48);
+    return _MAV_RETURN_uint8_t(msg,  52);
 }
 
 /**
@@ -459,6 +473,16 @@ static inline float mavlink_msg_ada_tm_get_msl_temperature(const mavlink_message
     return _MAV_RETURN_float(msg,  44);
 }
 
+/**
+ * @brief Get field dpl_altitude from ada_tm message
+ *
+ * @return [m] Main parachute deployment altituyde
+ */
+static inline float mavlink_msg_ada_tm_get_dpl_altitude(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  48);
+}
+
 /**
  * @brief Decode a ada_tm message into a struct
  *
@@ -479,6 +503,7 @@ static inline void mavlink_msg_ada_tm_decode(const mavlink_message_t* msg, mavli
     ada_tm->ref_temperature = mavlink_msg_ada_tm_get_ref_temperature(msg);
     ada_tm->msl_pressure = mavlink_msg_ada_tm_get_msl_pressure(msg);
     ada_tm->msl_temperature = mavlink_msg_ada_tm_get_msl_temperature(msg);
+    ada_tm->dpl_altitude = mavlink_msg_ada_tm_get_dpl_altitude(msg);
     ada_tm->state = mavlink_msg_ada_tm_get_state(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_ADA_TM_LEN? msg->len : MAVLINK_MSG_ID_ADA_TM_LEN;
diff --git a/mavlink_lib/pyxis/mavlink_msg_fsm_tm.h b/mavlink_lib/pyxis/mavlink_msg_fsm_tm.h
index b64c9f67d8534a0129f7a95afbe5fb5ab22285e1..5fc60088816ba5f4dce6687d1faa8e1b7520015e 100644
--- a/mavlink_lib/pyxis/mavlink_msg_fsm_tm.h
+++ b/mavlink_lib/pyxis/mavlink_msg_fsm_tm.h
@@ -10,17 +10,16 @@ typedef struct __mavlink_fsm_tm_t {
  uint8_t abk_state; /*<  Air Brakes state*/
  uint8_t dpl_state; /*<  Deployment state*/
  uint8_t fmm_state; /*<  Flight Mode Manager state*/
- uint8_t fsr_state; /*<  Flight Stats Recorder state*/
  uint8_t nas_state; /*<  Navigation and Attitude State state*/
 } mavlink_fsm_tm_t;
 
-#define MAVLINK_MSG_ID_FSM_TM_LEN 14
-#define MAVLINK_MSG_ID_FSM_TM_MIN_LEN 14
-#define MAVLINK_MSG_ID_201_LEN 14
-#define MAVLINK_MSG_ID_201_MIN_LEN 14
+#define MAVLINK_MSG_ID_FSM_TM_LEN 13
+#define MAVLINK_MSG_ID_FSM_TM_MIN_LEN 13
+#define MAVLINK_MSG_ID_201_LEN 13
+#define MAVLINK_MSG_ID_201_MIN_LEN 13
 
-#define MAVLINK_MSG_ID_FSM_TM_CRC 69
-#define MAVLINK_MSG_ID_201_CRC 69
+#define MAVLINK_MSG_ID_FSM_TM_CRC 253
+#define MAVLINK_MSG_ID_201_CRC 253
 
 
 
@@ -28,27 +27,25 @@ typedef struct __mavlink_fsm_tm_t {
 #define MAVLINK_MESSAGE_INFO_FSM_TM { \
     201, \
     "FSM_TM", \
-    7, \
+    6, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fsm_tm_t, timestamp) }, \
          { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fsm_tm_t, ada_state) }, \
          { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fsm_tm_t, abk_state) }, \
          { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fsm_tm_t, dpl_state) }, \
          { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fsm_tm_t, fmm_state) }, \
-         { "fsr_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_fsm_tm_t, fsr_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_fsm_tm_t, nas_state) }, \
+         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_fsm_tm_t, nas_state) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_FSM_TM { \
     "FSM_TM", \
-    7, \
+    6, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fsm_tm_t, timestamp) }, \
          { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fsm_tm_t, ada_state) }, \
          { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fsm_tm_t, abk_state) }, \
          { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fsm_tm_t, dpl_state) }, \
          { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fsm_tm_t, fmm_state) }, \
-         { "fsr_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_fsm_tm_t, fsr_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_fsm_tm_t, nas_state) }, \
+         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_fsm_tm_t, nas_state) }, \
          } \
 }
 #endif
@@ -64,12 +61,11 @@ typedef struct __mavlink_fsm_tm_t {
  * @param abk_state  Air Brakes state
  * @param dpl_state  Deployment state
  * @param fmm_state  Flight Mode Manager state
- * @param fsr_state  Flight Stats Recorder state
  * @param nas_state  Navigation and Attitude State state
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_fsm_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t fsr_state, uint8_t nas_state)
+                               uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
@@ -78,8 +74,7 @@ static inline uint16_t mavlink_msg_fsm_tm_pack(uint8_t system_id, uint8_t compon
     _mav_put_uint8_t(buf, 9, abk_state);
     _mav_put_uint8_t(buf, 10, dpl_state);
     _mav_put_uint8_t(buf, 11, fmm_state);
-    _mav_put_uint8_t(buf, 12, fsr_state);
-    _mav_put_uint8_t(buf, 13, nas_state);
+    _mav_put_uint8_t(buf, 12, nas_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FSM_TM_LEN);
 #else
@@ -89,7 +84,6 @@ static inline uint16_t mavlink_msg_fsm_tm_pack(uint8_t system_id, uint8_t compon
     packet.abk_state = abk_state;
     packet.dpl_state = dpl_state;
     packet.fmm_state = fmm_state;
-    packet.fsr_state = fsr_state;
     packet.nas_state = nas_state;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FSM_TM_LEN);
@@ -110,13 +104,12 @@ static inline uint16_t mavlink_msg_fsm_tm_pack(uint8_t system_id, uint8_t compon
  * @param abk_state  Air Brakes state
  * @param dpl_state  Deployment state
  * @param fmm_state  Flight Mode Manager state
- * @param fsr_state  Flight Stats Recorder state
  * @param nas_state  Navigation and Attitude State state
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_fsm_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,uint8_t ada_state,uint8_t abk_state,uint8_t dpl_state,uint8_t fmm_state,uint8_t fsr_state,uint8_t nas_state)
+                                   uint64_t timestamp,uint8_t ada_state,uint8_t abk_state,uint8_t dpl_state,uint8_t fmm_state,uint8_t nas_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
@@ -125,8 +118,7 @@ static inline uint16_t mavlink_msg_fsm_tm_pack_chan(uint8_t system_id, uint8_t c
     _mav_put_uint8_t(buf, 9, abk_state);
     _mav_put_uint8_t(buf, 10, dpl_state);
     _mav_put_uint8_t(buf, 11, fmm_state);
-    _mav_put_uint8_t(buf, 12, fsr_state);
-    _mav_put_uint8_t(buf, 13, nas_state);
+    _mav_put_uint8_t(buf, 12, nas_state);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FSM_TM_LEN);
 #else
@@ -136,7 +128,6 @@ static inline uint16_t mavlink_msg_fsm_tm_pack_chan(uint8_t system_id, uint8_t c
     packet.abk_state = abk_state;
     packet.dpl_state = dpl_state;
     packet.fmm_state = fmm_state;
-    packet.fsr_state = fsr_state;
     packet.nas_state = nas_state;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FSM_TM_LEN);
@@ -156,7 +147,7 @@ static inline uint16_t mavlink_msg_fsm_tm_pack_chan(uint8_t system_id, uint8_t c
  */
 static inline uint16_t mavlink_msg_fsm_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fsm_tm_t* fsm_tm)
 {
-    return mavlink_msg_fsm_tm_pack(system_id, component_id, msg, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->fsr_state, fsm_tm->nas_state);
+    return mavlink_msg_fsm_tm_pack(system_id, component_id, msg, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state);
 }
 
 /**
@@ -170,7 +161,7 @@ static inline uint16_t mavlink_msg_fsm_tm_encode(uint8_t system_id, uint8_t comp
  */
 static inline uint16_t mavlink_msg_fsm_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fsm_tm_t* fsm_tm)
 {
-    return mavlink_msg_fsm_tm_pack_chan(system_id, component_id, chan, msg, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->fsr_state, fsm_tm->nas_state);
+    return mavlink_msg_fsm_tm_pack_chan(system_id, component_id, chan, msg, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state);
 }
 
 /**
@@ -182,12 +173,11 @@ static inline uint16_t mavlink_msg_fsm_tm_encode_chan(uint8_t system_id, uint8_t
  * @param abk_state  Air Brakes state
  * @param dpl_state  Deployment state
  * @param fmm_state  Flight Mode Manager state
- * @param fsr_state  Flight Stats Recorder state
  * @param nas_state  Navigation and Attitude State state
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_fsm_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t fsr_state, uint8_t nas_state)
+static inline void mavlink_msg_fsm_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
@@ -196,8 +186,7 @@ static inline void mavlink_msg_fsm_tm_send(mavlink_channel_t chan, uint64_t time
     _mav_put_uint8_t(buf, 9, abk_state);
     _mav_put_uint8_t(buf, 10, dpl_state);
     _mav_put_uint8_t(buf, 11, fmm_state);
-    _mav_put_uint8_t(buf, 12, fsr_state);
-    _mav_put_uint8_t(buf, 13, nas_state);
+    _mav_put_uint8_t(buf, 12, nas_state);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, buf, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
 #else
@@ -207,7 +196,6 @@ static inline void mavlink_msg_fsm_tm_send(mavlink_channel_t chan, uint64_t time
     packet.abk_state = abk_state;
     packet.dpl_state = dpl_state;
     packet.fmm_state = fmm_state;
-    packet.fsr_state = fsr_state;
     packet.nas_state = nas_state;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)&packet, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
@@ -222,7 +210,7 @@ static inline void mavlink_msg_fsm_tm_send(mavlink_channel_t chan, uint64_t time
 static inline void mavlink_msg_fsm_tm_send_struct(mavlink_channel_t chan, const mavlink_fsm_tm_t* fsm_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_fsm_tm_send(chan, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->fsr_state, fsm_tm->nas_state);
+    mavlink_msg_fsm_tm_send(chan, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)fsm_tm, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
 #endif
@@ -236,7 +224,7 @@ static inline void mavlink_msg_fsm_tm_send_struct(mavlink_channel_t chan, const
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_fsm_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t fsr_state, uint8_t nas_state)
+static inline void mavlink_msg_fsm_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -245,8 +233,7 @@ static inline void mavlink_msg_fsm_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     _mav_put_uint8_t(buf, 9, abk_state);
     _mav_put_uint8_t(buf, 10, dpl_state);
     _mav_put_uint8_t(buf, 11, fmm_state);
-    _mav_put_uint8_t(buf, 12, fsr_state);
-    _mav_put_uint8_t(buf, 13, nas_state);
+    _mav_put_uint8_t(buf, 12, nas_state);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, buf, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
 #else
@@ -256,7 +243,6 @@ static inline void mavlink_msg_fsm_tm_send_buf(mavlink_message_t *msgbuf, mavlin
     packet->abk_state = abk_state;
     packet->dpl_state = dpl_state;
     packet->fmm_state = fmm_state;
-    packet->fsr_state = fsr_state;
     packet->nas_state = nas_state;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)packet, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
@@ -319,16 +305,6 @@ static inline uint8_t mavlink_msg_fsm_tm_get_fmm_state(const mavlink_message_t*
     return _MAV_RETURN_uint8_t(msg,  11);
 }
 
-/**
- * @brief Get field fsr_state from fsm_tm message
- *
- * @return  Flight Stats Recorder state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_fsr_state(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint8_t(msg,  12);
-}
-
 /**
  * @brief Get field nas_state from fsm_tm message
  *
@@ -336,7 +312,7 @@ static inline uint8_t mavlink_msg_fsm_tm_get_fsr_state(const mavlink_message_t*
  */
 static inline uint8_t mavlink_msg_fsm_tm_get_nas_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  13);
+    return _MAV_RETURN_uint8_t(msg,  12);
 }
 
 /**
@@ -353,7 +329,6 @@ static inline void mavlink_msg_fsm_tm_decode(const mavlink_message_t* msg, mavli
     fsm_tm->abk_state = mavlink_msg_fsm_tm_get_abk_state(msg);
     fsm_tm->dpl_state = mavlink_msg_fsm_tm_get_dpl_state(msg);
     fsm_tm->fmm_state = mavlink_msg_fsm_tm_get_fmm_state(msg);
-    fsm_tm->fsr_state = mavlink_msg_fsm_tm_get_fsr_state(msg);
     fsm_tm->nas_state = mavlink_msg_fsm_tm_get_nas_state(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_FSM_TM_LEN? msg->len : MAVLINK_MSG_ID_FSM_TM_LEN;
diff --git a/mavlink_lib/pyxis/mavlink_msg_rocket_flight_tm.h b/mavlink_lib/pyxis/mavlink_msg_rocket_flight_tm.h
index f838fb425a520d0343c72313b3e0f6c911e5c97d..68a90717dd7262179571b62de8bbabe96efe2c78 100644
--- a/mavlink_lib/pyxis/mavlink_msg_rocket_flight_tm.h
+++ b/mavlink_lib/pyxis/mavlink_msg_rocket_flight_tm.h
@@ -27,6 +27,7 @@ typedef struct __mavlink_rocket_flight_tm_t {
  float gps_alt; /*< [m] GPS Altitude*/
  float abk_angle; /*< [deg] Air Brakes angle*/
  float abk_estimated_cd; /*<  Estimated drag coefficient*/
+ float parachute_load; /*<  Parachute load cell value*/
  float nas_n; /*< [deg] Navigation system estimated noth position*/
  float nas_e; /*< [deg] Navigation system estimated east position*/
  float nas_d; /*< [m] Navigation system estimated down position*/
@@ -55,13 +56,13 @@ typedef struct __mavlink_rocket_flight_tm_t {
  int8_t logger_error; /*<  Logger error (0 = no error, -1 otherwise)*/
 } mavlink_rocket_flight_tm_t;
 
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN 163
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN 163
-#define MAVLINK_MSG_ID_208_LEN 163
-#define MAVLINK_MSG_ID_208_MIN_LEN 163
+#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN 167
+#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN 167
+#define MAVLINK_MSG_ID_208_LEN 167
+#define MAVLINK_MSG_ID_208_MIN_LEN 167
 
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC 189
-#define MAVLINK_MSG_ID_208_CRC 189
+#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC 184
+#define MAVLINK_MSG_ID_208_CRC 184
 
 
 
@@ -69,13 +70,13 @@ typedef struct __mavlink_rocket_flight_tm_t {
 #define MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM { \
     208, \
     "ROCKET_FLIGHT_TM", \
-    48, \
+    49, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \
-         { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 152, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 153, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
-         { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 154, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
-         { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 155, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
+         { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
+         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
+         { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
+         { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
+         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
          { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rocket_flight_tm_t, pressure_ada) }, \
          { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rocket_flight_tm_t, pressure_digi) }, \
          { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rocket_flight_tm_t, pressure_static) }, \
@@ -92,44 +93,45 @@ typedef struct __mavlink_rocket_flight_tm_t {
          { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \
          { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \
          { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
          { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \
          { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \
          { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \
          { "abk_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, abk_angle) }, \
          { "abk_estimated_cd", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_rocket_flight_tm_t, abk_estimated_cd) }, \
-         { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \
-         { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \
-         { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \
-         { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \
-         { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \
-         { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \
-         { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \
-         { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \
-         { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \
-         { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \
-         { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
-         { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
-         { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
-         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
-         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
-         { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
-         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
-         { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, vbat) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
-         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 162, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
+         { "parachute_load", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, parachute_load) }, \
+         { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \
+         { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \
+         { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \
+         { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \
+         { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \
+         { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \
+         { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \
+         { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \
+         { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \
+         { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \
+         { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
+         { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
+         { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
+         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
+         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
+         { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
+         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
+         { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, vbat) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
+         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM { \
     "ROCKET_FLIGHT_TM", \
-    48, \
+    49, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \
-         { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 152, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
-         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 153, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
-         { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 154, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
-         { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 155, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
-         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
+         { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
+         { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
+         { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
+         { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
+         { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
          { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rocket_flight_tm_t, pressure_ada) }, \
          { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rocket_flight_tm_t, pressure_digi) }, \
          { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rocket_flight_tm_t, pressure_static) }, \
@@ -146,32 +148,33 @@ typedef struct __mavlink_rocket_flight_tm_t {
          { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \
          { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \
          { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \
-         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
+         { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
          { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \
          { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \
          { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \
          { "abk_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, abk_angle) }, \
          { "abk_estimated_cd", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_rocket_flight_tm_t, abk_estimated_cd) }, \
-         { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \
-         { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \
-         { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \
-         { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \
-         { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \
-         { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \
-         { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \
-         { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \
-         { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \
-         { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \
-         { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
-         { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
-         { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
-         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
-         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
-         { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
-         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
-         { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, vbat) }, \
-         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
-         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 162, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
+         { "parachute_load", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, parachute_load) }, \
+         { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \
+         { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \
+         { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \
+         { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \
+         { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \
+         { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \
+         { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \
+         { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \
+         { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \
+         { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \
+         { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
+         { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
+         { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
+         { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
+         { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
+         { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
+         { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
+         { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, vbat) }, \
+         { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
+         { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
          } \
 }
 #endif
@@ -210,6 +213,7 @@ typedef struct __mavlink_rocket_flight_tm_t {
  * @param gps_alt [m] GPS Altitude
  * @param abk_angle [deg] Air Brakes angle
  * @param abk_estimated_cd  Estimated drag coefficient
+ * @param parachute_load  Parachute load cell value
  * @param nas_n [deg] Navigation system estimated noth position
  * @param nas_e [deg] Navigation system estimated east position
  * @param nas_d [m] Navigation system estimated down position
@@ -233,7 +237,7 @@ typedef struct __mavlink_rocket_flight_tm_t {
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float abk_estimated_cd, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float vbat, float temperature, int8_t logger_error)
+                               uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float abk_estimated_cd, float parachute_load, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float vbat, float temperature, int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
@@ -259,32 +263,33 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
     _mav_put_float(buf, 80, gps_alt);
     _mav_put_float(buf, 84, abk_angle);
     _mav_put_float(buf, 88, abk_estimated_cd);
-    _mav_put_float(buf, 92, nas_n);
-    _mav_put_float(buf, 96, nas_e);
-    _mav_put_float(buf, 100, nas_d);
-    _mav_put_float(buf, 104, nas_vn);
-    _mav_put_float(buf, 108, nas_ve);
-    _mav_put_float(buf, 112, nas_vd);
-    _mav_put_float(buf, 116, nas_qx);
-    _mav_put_float(buf, 120, nas_qy);
-    _mav_put_float(buf, 124, nas_qz);
-    _mav_put_float(buf, 128, nas_qw);
-    _mav_put_float(buf, 132, nas_bias_x);
-    _mav_put_float(buf, 136, nas_bias_y);
-    _mav_put_float(buf, 140, nas_bias_z);
-    _mav_put_float(buf, 144, vbat);
-    _mav_put_float(buf, 148, temperature);
-    _mav_put_uint8_t(buf, 152, ada_state);
-    _mav_put_uint8_t(buf, 153, fmm_state);
-    _mav_put_uint8_t(buf, 154, dpl_state);
-    _mav_put_uint8_t(buf, 155, abk_state);
-    _mav_put_uint8_t(buf, 156, nas_state);
-    _mav_put_uint8_t(buf, 157, gps_fix);
-    _mav_put_uint8_t(buf, 158, pin_launch);
-    _mav_put_uint8_t(buf, 159, pin_nosecone);
-    _mav_put_uint8_t(buf, 160, pin_expulsion);
-    _mav_put_uint8_t(buf, 161, cutter_presence);
-    _mav_put_int8_t(buf, 162, logger_error);
+    _mav_put_float(buf, 92, parachute_load);
+    _mav_put_float(buf, 96, nas_n);
+    _mav_put_float(buf, 100, nas_e);
+    _mav_put_float(buf, 104, nas_d);
+    _mav_put_float(buf, 108, nas_vn);
+    _mav_put_float(buf, 112, nas_ve);
+    _mav_put_float(buf, 116, nas_vd);
+    _mav_put_float(buf, 120, nas_qx);
+    _mav_put_float(buf, 124, nas_qy);
+    _mav_put_float(buf, 128, nas_qz);
+    _mav_put_float(buf, 132, nas_qw);
+    _mav_put_float(buf, 136, nas_bias_x);
+    _mav_put_float(buf, 140, nas_bias_y);
+    _mav_put_float(buf, 144, nas_bias_z);
+    _mav_put_float(buf, 148, vbat);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, ada_state);
+    _mav_put_uint8_t(buf, 157, fmm_state);
+    _mav_put_uint8_t(buf, 158, dpl_state);
+    _mav_put_uint8_t(buf, 159, abk_state);
+    _mav_put_uint8_t(buf, 160, nas_state);
+    _mav_put_uint8_t(buf, 161, gps_fix);
+    _mav_put_uint8_t(buf, 162, pin_launch);
+    _mav_put_uint8_t(buf, 163, pin_nosecone);
+    _mav_put_uint8_t(buf, 164, pin_expulsion);
+    _mav_put_uint8_t(buf, 165, cutter_presence);
+    _mav_put_int8_t(buf, 166, logger_error);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
 #else
@@ -311,6 +316,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
     packet.gps_alt = gps_alt;
     packet.abk_angle = abk_angle;
     packet.abk_estimated_cd = abk_estimated_cd;
+    packet.parachute_load = parachute_load;
     packet.nas_n = nas_n;
     packet.nas_e = nas_e;
     packet.nas_d = nas_d;
@@ -379,6 +385,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
  * @param gps_alt [m] GPS Altitude
  * @param abk_angle [deg] Air Brakes angle
  * @param abk_estimated_cd  Estimated drag coefficient
+ * @param parachute_load  Parachute load cell value
  * @param nas_n [deg] Navigation system estimated noth position
  * @param nas_e [deg] Navigation system estimated east position
  * @param nas_d [m] Navigation system estimated down position
@@ -403,7 +410,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint
  */
 static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint64_t timestamp,uint8_t ada_state,uint8_t fmm_state,uint8_t dpl_state,uint8_t abk_state,uint8_t nas_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float ada_vert_speed,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float abk_angle,float abk_estimated_cd,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t pin_expulsion,uint8_t cutter_presence,float vbat,float temperature,int8_t logger_error)
+                                   uint64_t timestamp,uint8_t ada_state,uint8_t fmm_state,uint8_t dpl_state,uint8_t abk_state,uint8_t nas_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float ada_vert_speed,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float abk_angle,float abk_estimated_cd,float parachute_load,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t pin_expulsion,uint8_t cutter_presence,float vbat,float temperature,int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
@@ -429,32 +436,33 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id,
     _mav_put_float(buf, 80, gps_alt);
     _mav_put_float(buf, 84, abk_angle);
     _mav_put_float(buf, 88, abk_estimated_cd);
-    _mav_put_float(buf, 92, nas_n);
-    _mav_put_float(buf, 96, nas_e);
-    _mav_put_float(buf, 100, nas_d);
-    _mav_put_float(buf, 104, nas_vn);
-    _mav_put_float(buf, 108, nas_ve);
-    _mav_put_float(buf, 112, nas_vd);
-    _mav_put_float(buf, 116, nas_qx);
-    _mav_put_float(buf, 120, nas_qy);
-    _mav_put_float(buf, 124, nas_qz);
-    _mav_put_float(buf, 128, nas_qw);
-    _mav_put_float(buf, 132, nas_bias_x);
-    _mav_put_float(buf, 136, nas_bias_y);
-    _mav_put_float(buf, 140, nas_bias_z);
-    _mav_put_float(buf, 144, vbat);
-    _mav_put_float(buf, 148, temperature);
-    _mav_put_uint8_t(buf, 152, ada_state);
-    _mav_put_uint8_t(buf, 153, fmm_state);
-    _mav_put_uint8_t(buf, 154, dpl_state);
-    _mav_put_uint8_t(buf, 155, abk_state);
-    _mav_put_uint8_t(buf, 156, nas_state);
-    _mav_put_uint8_t(buf, 157, gps_fix);
-    _mav_put_uint8_t(buf, 158, pin_launch);
-    _mav_put_uint8_t(buf, 159, pin_nosecone);
-    _mav_put_uint8_t(buf, 160, pin_expulsion);
-    _mav_put_uint8_t(buf, 161, cutter_presence);
-    _mav_put_int8_t(buf, 162, logger_error);
+    _mav_put_float(buf, 92, parachute_load);
+    _mav_put_float(buf, 96, nas_n);
+    _mav_put_float(buf, 100, nas_e);
+    _mav_put_float(buf, 104, nas_d);
+    _mav_put_float(buf, 108, nas_vn);
+    _mav_put_float(buf, 112, nas_ve);
+    _mav_put_float(buf, 116, nas_vd);
+    _mav_put_float(buf, 120, nas_qx);
+    _mav_put_float(buf, 124, nas_qy);
+    _mav_put_float(buf, 128, nas_qz);
+    _mav_put_float(buf, 132, nas_qw);
+    _mav_put_float(buf, 136, nas_bias_x);
+    _mav_put_float(buf, 140, nas_bias_y);
+    _mav_put_float(buf, 144, nas_bias_z);
+    _mav_put_float(buf, 148, vbat);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, ada_state);
+    _mav_put_uint8_t(buf, 157, fmm_state);
+    _mav_put_uint8_t(buf, 158, dpl_state);
+    _mav_put_uint8_t(buf, 159, abk_state);
+    _mav_put_uint8_t(buf, 160, nas_state);
+    _mav_put_uint8_t(buf, 161, gps_fix);
+    _mav_put_uint8_t(buf, 162, pin_launch);
+    _mav_put_uint8_t(buf, 163, pin_nosecone);
+    _mav_put_uint8_t(buf, 164, pin_expulsion);
+    _mav_put_uint8_t(buf, 165, cutter_presence);
+    _mav_put_int8_t(buf, 166, logger_error);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
 #else
@@ -481,6 +489,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id,
     packet.gps_alt = gps_alt;
     packet.abk_angle = abk_angle;
     packet.abk_estimated_cd = abk_estimated_cd;
+    packet.parachute_load = parachute_load;
     packet.nas_n = nas_n;
     packet.nas_e = nas_e;
     packet.nas_d = nas_d;
@@ -525,7 +534,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id,
  */
 static inline uint16_t mavlink_msg_rocket_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
 {
-    return mavlink_msg_rocket_flight_tm_pack(system_id, component_id, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->abk_estimated_cd, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->vbat, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
+    return mavlink_msg_rocket_flight_tm_pack(system_id, component_id, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->abk_estimated_cd, rocket_flight_tm->parachute_load, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->vbat, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
 }
 
 /**
@@ -539,7 +548,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode(uint8_t system_id, ui
  */
 static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
 {
-    return mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, chan, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->abk_estimated_cd, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->vbat, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
+    return mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, chan, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->abk_estimated_cd, rocket_flight_tm->parachute_load, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->vbat, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
 }
 
 /**
@@ -574,6 +583,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_i
  * @param gps_alt [m] GPS Altitude
  * @param abk_angle [deg] Air Brakes angle
  * @param abk_estimated_cd  Estimated drag coefficient
+ * @param parachute_load  Parachute load cell value
  * @param nas_n [deg] Navigation system estimated noth position
  * @param nas_e [deg] Navigation system estimated east position
  * @param nas_d [m] Navigation system estimated down position
@@ -597,7 +607,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_i
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float abk_estimated_cd, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float vbat, float temperature, int8_t logger_error)
+static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float abk_estimated_cd, float parachute_load, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float vbat, float temperature, int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
@@ -623,32 +633,33 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin
     _mav_put_float(buf, 80, gps_alt);
     _mav_put_float(buf, 84, abk_angle);
     _mav_put_float(buf, 88, abk_estimated_cd);
-    _mav_put_float(buf, 92, nas_n);
-    _mav_put_float(buf, 96, nas_e);
-    _mav_put_float(buf, 100, nas_d);
-    _mav_put_float(buf, 104, nas_vn);
-    _mav_put_float(buf, 108, nas_ve);
-    _mav_put_float(buf, 112, nas_vd);
-    _mav_put_float(buf, 116, nas_qx);
-    _mav_put_float(buf, 120, nas_qy);
-    _mav_put_float(buf, 124, nas_qz);
-    _mav_put_float(buf, 128, nas_qw);
-    _mav_put_float(buf, 132, nas_bias_x);
-    _mav_put_float(buf, 136, nas_bias_y);
-    _mav_put_float(buf, 140, nas_bias_z);
-    _mav_put_float(buf, 144, vbat);
-    _mav_put_float(buf, 148, temperature);
-    _mav_put_uint8_t(buf, 152, ada_state);
-    _mav_put_uint8_t(buf, 153, fmm_state);
-    _mav_put_uint8_t(buf, 154, dpl_state);
-    _mav_put_uint8_t(buf, 155, abk_state);
-    _mav_put_uint8_t(buf, 156, nas_state);
-    _mav_put_uint8_t(buf, 157, gps_fix);
-    _mav_put_uint8_t(buf, 158, pin_launch);
-    _mav_put_uint8_t(buf, 159, pin_nosecone);
-    _mav_put_uint8_t(buf, 160, pin_expulsion);
-    _mav_put_uint8_t(buf, 161, cutter_presence);
-    _mav_put_int8_t(buf, 162, logger_error);
+    _mav_put_float(buf, 92, parachute_load);
+    _mav_put_float(buf, 96, nas_n);
+    _mav_put_float(buf, 100, nas_e);
+    _mav_put_float(buf, 104, nas_d);
+    _mav_put_float(buf, 108, nas_vn);
+    _mav_put_float(buf, 112, nas_ve);
+    _mav_put_float(buf, 116, nas_vd);
+    _mav_put_float(buf, 120, nas_qx);
+    _mav_put_float(buf, 124, nas_qy);
+    _mav_put_float(buf, 128, nas_qz);
+    _mav_put_float(buf, 132, nas_qw);
+    _mav_put_float(buf, 136, nas_bias_x);
+    _mav_put_float(buf, 140, nas_bias_y);
+    _mav_put_float(buf, 144, nas_bias_z);
+    _mav_put_float(buf, 148, vbat);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, ada_state);
+    _mav_put_uint8_t(buf, 157, fmm_state);
+    _mav_put_uint8_t(buf, 158, dpl_state);
+    _mav_put_uint8_t(buf, 159, abk_state);
+    _mav_put_uint8_t(buf, 160, nas_state);
+    _mav_put_uint8_t(buf, 161, gps_fix);
+    _mav_put_uint8_t(buf, 162, pin_launch);
+    _mav_put_uint8_t(buf, 163, pin_nosecone);
+    _mav_put_uint8_t(buf, 164, pin_expulsion);
+    _mav_put_uint8_t(buf, 165, cutter_presence);
+    _mav_put_int8_t(buf, 166, logger_error);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
 #else
@@ -675,6 +686,7 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin
     packet.gps_alt = gps_alt;
     packet.abk_angle = abk_angle;
     packet.abk_estimated_cd = abk_estimated_cd;
+    packet.parachute_load = parachute_load;
     packet.nas_n = nas_n;
     packet.nas_e = nas_e;
     packet.nas_d = nas_d;
@@ -714,7 +726,7 @@ static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uin
 static inline void mavlink_msg_rocket_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_rocket_flight_tm_send(chan, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->abk_estimated_cd, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->vbat, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
+    mavlink_msg_rocket_flight_tm_send(chan, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->abk_estimated_cd, rocket_flight_tm->parachute_load, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->vbat, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)rocket_flight_tm, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
 #endif
@@ -728,7 +740,7 @@ static inline void mavlink_msg_rocket_flight_tm_send_struct(mavlink_channel_t ch
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float abk_estimated_cd, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float vbat, float temperature, int8_t logger_error)
+static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float abk_estimated_cd, float parachute_load, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float vbat, float temperature, int8_t logger_error)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -754,32 +766,33 @@ static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgb
     _mav_put_float(buf, 80, gps_alt);
     _mav_put_float(buf, 84, abk_angle);
     _mav_put_float(buf, 88, abk_estimated_cd);
-    _mav_put_float(buf, 92, nas_n);
-    _mav_put_float(buf, 96, nas_e);
-    _mav_put_float(buf, 100, nas_d);
-    _mav_put_float(buf, 104, nas_vn);
-    _mav_put_float(buf, 108, nas_ve);
-    _mav_put_float(buf, 112, nas_vd);
-    _mav_put_float(buf, 116, nas_qx);
-    _mav_put_float(buf, 120, nas_qy);
-    _mav_put_float(buf, 124, nas_qz);
-    _mav_put_float(buf, 128, nas_qw);
-    _mav_put_float(buf, 132, nas_bias_x);
-    _mav_put_float(buf, 136, nas_bias_y);
-    _mav_put_float(buf, 140, nas_bias_z);
-    _mav_put_float(buf, 144, vbat);
-    _mav_put_float(buf, 148, temperature);
-    _mav_put_uint8_t(buf, 152, ada_state);
-    _mav_put_uint8_t(buf, 153, fmm_state);
-    _mav_put_uint8_t(buf, 154, dpl_state);
-    _mav_put_uint8_t(buf, 155, abk_state);
-    _mav_put_uint8_t(buf, 156, nas_state);
-    _mav_put_uint8_t(buf, 157, gps_fix);
-    _mav_put_uint8_t(buf, 158, pin_launch);
-    _mav_put_uint8_t(buf, 159, pin_nosecone);
-    _mav_put_uint8_t(buf, 160, pin_expulsion);
-    _mav_put_uint8_t(buf, 161, cutter_presence);
-    _mav_put_int8_t(buf, 162, logger_error);
+    _mav_put_float(buf, 92, parachute_load);
+    _mav_put_float(buf, 96, nas_n);
+    _mav_put_float(buf, 100, nas_e);
+    _mav_put_float(buf, 104, nas_d);
+    _mav_put_float(buf, 108, nas_vn);
+    _mav_put_float(buf, 112, nas_ve);
+    _mav_put_float(buf, 116, nas_vd);
+    _mav_put_float(buf, 120, nas_qx);
+    _mav_put_float(buf, 124, nas_qy);
+    _mav_put_float(buf, 128, nas_qz);
+    _mav_put_float(buf, 132, nas_qw);
+    _mav_put_float(buf, 136, nas_bias_x);
+    _mav_put_float(buf, 140, nas_bias_y);
+    _mav_put_float(buf, 144, nas_bias_z);
+    _mav_put_float(buf, 148, vbat);
+    _mav_put_float(buf, 152, temperature);
+    _mav_put_uint8_t(buf, 156, ada_state);
+    _mav_put_uint8_t(buf, 157, fmm_state);
+    _mav_put_uint8_t(buf, 158, dpl_state);
+    _mav_put_uint8_t(buf, 159, abk_state);
+    _mav_put_uint8_t(buf, 160, nas_state);
+    _mav_put_uint8_t(buf, 161, gps_fix);
+    _mav_put_uint8_t(buf, 162, pin_launch);
+    _mav_put_uint8_t(buf, 163, pin_nosecone);
+    _mav_put_uint8_t(buf, 164, pin_expulsion);
+    _mav_put_uint8_t(buf, 165, cutter_presence);
+    _mav_put_int8_t(buf, 166, logger_error);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
 #else
@@ -806,6 +819,7 @@ static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgb
     packet->gps_alt = gps_alt;
     packet->abk_angle = abk_angle;
     packet->abk_estimated_cd = abk_estimated_cd;
+    packet->parachute_load = parachute_load;
     packet->nas_n = nas_n;
     packet->nas_e = nas_e;
     packet->nas_d = nas_d;
@@ -860,7 +874,7 @@ static inline uint64_t mavlink_msg_rocket_flight_tm_get_timestamp(const mavlink_
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_ada_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  152);
+    return _MAV_RETURN_uint8_t(msg,  156);
 }
 
 /**
@@ -870,7 +884,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_ada_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_fmm_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  153);
+    return _MAV_RETURN_uint8_t(msg,  157);
 }
 
 /**
@@ -880,7 +894,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_fmm_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_dpl_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  154);
+    return _MAV_RETURN_uint8_t(msg,  158);
 }
 
 /**
@@ -890,7 +904,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_dpl_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_abk_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  155);
+    return _MAV_RETURN_uint8_t(msg,  159);
 }
 
 /**
@@ -900,7 +914,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_abk_state(const mavlink_m
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_nas_state(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  156);
+    return _MAV_RETURN_uint8_t(msg,  160);
 }
 
 /**
@@ -1070,7 +1084,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_mag_z(const mavlink_message
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_gps_fix(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  157);
+    return _MAV_RETURN_uint8_t(msg,  161);
 }
 
 /**
@@ -1123,6 +1137,16 @@ static inline float mavlink_msg_rocket_flight_tm_get_abk_estimated_cd(const mavl
     return _MAV_RETURN_float(msg,  88);
 }
 
+/**
+ * @brief Get field parachute_load from rocket_flight_tm message
+ *
+ * @return  Parachute load cell value
+ */
+static inline float mavlink_msg_rocket_flight_tm_get_parachute_load(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  92);
+}
+
 /**
  * @brief Get field nas_n from rocket_flight_tm message
  *
@@ -1130,7 +1154,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_abk_estimated_cd(const mavl
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_n(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  92);
+    return _MAV_RETURN_float(msg,  96);
 }
 
 /**
@@ -1140,7 +1164,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_n(const mavlink_message
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_e(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  96);
+    return _MAV_RETURN_float(msg,  100);
 }
 
 /**
@@ -1150,7 +1174,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_e(const mavlink_message
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_d(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  100);
+    return _MAV_RETURN_float(msg,  104);
 }
 
 /**
@@ -1160,7 +1184,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_d(const mavlink_message
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_vn(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  104);
+    return _MAV_RETURN_float(msg,  108);
 }
 
 /**
@@ -1170,7 +1194,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_vn(const mavlink_messag
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_ve(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  108);
+    return _MAV_RETURN_float(msg,  112);
 }
 
 /**
@@ -1180,7 +1204,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_ve(const mavlink_messag
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_vd(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  112);
+    return _MAV_RETURN_float(msg,  116);
 }
 
 /**
@@ -1190,7 +1214,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_vd(const mavlink_messag
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_qx(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  116);
+    return _MAV_RETURN_float(msg,  120);
 }
 
 /**
@@ -1200,7 +1224,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_qx(const mavlink_messag
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_qy(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  120);
+    return _MAV_RETURN_float(msg,  124);
 }
 
 /**
@@ -1210,7 +1234,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_qy(const mavlink_messag
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_qz(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  124);
+    return _MAV_RETURN_float(msg,  128);
 }
 
 /**
@@ -1220,7 +1244,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_qz(const mavlink_messag
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_qw(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  128);
+    return _MAV_RETURN_float(msg,  132);
 }
 
 /**
@@ -1230,7 +1254,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_qw(const mavlink_messag
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_x(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  132);
+    return _MAV_RETURN_float(msg,  136);
 }
 
 /**
@@ -1240,7 +1264,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_x(const mavlink_me
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_y(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  136);
+    return _MAV_RETURN_float(msg,  140);
 }
 
 /**
@@ -1250,7 +1274,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_y(const mavlink_me
  */
 static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_z(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  140);
+    return _MAV_RETURN_float(msg,  144);
 }
 
 /**
@@ -1260,7 +1284,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_z(const mavlink_me
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_launch(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  158);
+    return _MAV_RETURN_uint8_t(msg,  162);
 }
 
 /**
@@ -1270,7 +1294,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_launch(const mavlink_
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_nosecone(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  159);
+    return _MAV_RETURN_uint8_t(msg,  163);
 }
 
 /**
@@ -1280,7 +1304,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_nosecone(const mavlin
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_expulsion(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  160);
+    return _MAV_RETURN_uint8_t(msg,  164);
 }
 
 /**
@@ -1290,7 +1314,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_expulsion(const mavli
  */
 static inline uint8_t mavlink_msg_rocket_flight_tm_get_cutter_presence(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  161);
+    return _MAV_RETURN_uint8_t(msg,  165);
 }
 
 /**
@@ -1300,7 +1324,7 @@ static inline uint8_t mavlink_msg_rocket_flight_tm_get_cutter_presence(const mav
  */
 static inline float mavlink_msg_rocket_flight_tm_get_vbat(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  144);
+    return _MAV_RETURN_float(msg,  148);
 }
 
 /**
@@ -1310,7 +1334,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_vbat(const mavlink_message_
  */
 static inline float mavlink_msg_rocket_flight_tm_get_temperature(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_float(msg,  148);
+    return _MAV_RETURN_float(msg,  152);
 }
 
 /**
@@ -1320,7 +1344,7 @@ static inline float mavlink_msg_rocket_flight_tm_get_temperature(const mavlink_m
  */
 static inline int8_t mavlink_msg_rocket_flight_tm_get_logger_error(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_int8_t(msg,  162);
+    return _MAV_RETURN_int8_t(msg,  166);
 }
 
 /**
@@ -1354,6 +1378,7 @@ static inline void mavlink_msg_rocket_flight_tm_decode(const mavlink_message_t*
     rocket_flight_tm->gps_alt = mavlink_msg_rocket_flight_tm_get_gps_alt(msg);
     rocket_flight_tm->abk_angle = mavlink_msg_rocket_flight_tm_get_abk_angle(msg);
     rocket_flight_tm->abk_estimated_cd = mavlink_msg_rocket_flight_tm_get_abk_estimated_cd(msg);
+    rocket_flight_tm->parachute_load = mavlink_msg_rocket_flight_tm_get_parachute_load(msg);
     rocket_flight_tm->nas_n = mavlink_msg_rocket_flight_tm_get_nas_n(msg);
     rocket_flight_tm->nas_e = mavlink_msg_rocket_flight_tm_get_nas_e(msg);
     rocket_flight_tm->nas_d = mavlink_msg_rocket_flight_tm_get_nas_d(msg);
diff --git a/mavlink_lib/pyxis/pyxis.h b/mavlink_lib/pyxis/pyxis.h
index 72668e72dcfce8ada8f5218fef92f3811e0d5a80..5535c65e1108b9f1fd5d288cd2c9978754c68faf 100644
--- a/mavlink_lib/pyxis/pyxis.h
+++ b/mavlink_lib/pyxis/pyxis.h
@@ -11,7 +11,7 @@
 #endif
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -1786394334196858732
+#define MAVLINK_THIS_XML_HASH -7023161531361269467
 
 #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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 49, 77, 30, 163, 158, 92, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 13, 46, 28, 27, 53, 77, 0, 167, 158, 92, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
 #endif
 
 #ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 103, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 39, 178, 239, 104, 175, 222, 128, 233, 170, 42, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 69, 142, 108, 133, 79, 66, 169, 189, 193, 245, 115, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 103, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 39, 178, 239, 104, 175, 222, 128, 233, 170, 42, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 253, 142, 108, 133, 234, 66, 0, 184, 193, 245, 115, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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"
@@ -177,7 +177,6 @@ typedef enum PinsList
 #include "./mavlink_msg_task_stats_tm.h"
 #include "./mavlink_msg_ada_tm.h"
 #include "./mavlink_msg_nas_tm.h"
-#include "./mavlink_msg_can_tm.h"
 #include "./mavlink_msg_rocket_flight_tm.h"
 #include "./mavlink_msg_payload_flight_tm.h"
 #include "./mavlink_msg_rocket_stats_tm.h"
@@ -187,11 +186,11 @@ typedef enum PinsList
 
 
 #undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -1786394334196858732
+#define MAVLINK_THIS_XML_HASH -7023161531361269467
 
 #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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_FSM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_CAN_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
-# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 105 }, { "ATTITUDE_TM", 110 }, { "CAN_TM", 207 }, { "COMMAND_TC", 2 }, { "CURRENT_TM", 107 }, { "FSM_TM", 201 }, { "GPS_TM", 102 }, { "IMU_TM", 103 }, { "LOAD_TM", 109 }, { "LOGGER_TM", 202 }, { "MAVLINK_STATS_TM", 203 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 113 }, { "PRESSURE_TM", 104 }, { "RAW_EVENT_TC", 13 }, { "RESET_SERVO_TC", 8 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 111 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 112 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 16 }, { "SET_COORDINATES_TC", 12 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 14 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_TARGET_COORDINATES_TC", 15 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 108 }, { "VOLTAGE_TM", 106 }, { "WIGGLE_SERVO_TC", 7 }}
+# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
+# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 105 }, { "ATTITUDE_TM", 110 }, { "COMMAND_TC", 2 }, { "CURRENT_TM", 107 }, { "FSM_TM", 201 }, { "GPS_TM", 102 }, { "IMU_TM", 103 }, { "LOAD_TM", 109 }, { "LOGGER_TM", 202 }, { "MAVLINK_STATS_TM", 203 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 113 }, { "PRESSURE_TM", 104 }, { "RAW_EVENT_TC", 13 }, { "RESET_SERVO_TC", 8 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 111 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 112 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 16 }, { "SET_COORDINATES_TC", 12 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 14 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_TARGET_COORDINATES_TC", 15 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 108 }, { "VOLTAGE_TM", 106 }, { "WIGGLE_SERVO_TC", 7 }}
 # if MAVLINK_COMMAND_24BIT
 #  include "../mavlink_get_info.h"
 # endif
diff --git a/mavlink_lib/pyxis/testsuite.h b/mavlink_lib/pyxis/testsuite.h
index 7c3e750a75bebf49c99856802d762b7e2238afbd..3078acaef9f74a21f0642f2b10d393b85ab72c69 100644
--- a/mavlink_lib/pyxis/testsuite.h
+++ b/mavlink_lib/pyxis/testsuite.h
@@ -1930,7 +1930,7 @@ static void mavlink_test_fsm_tm(uint8_t system_id, uint8_t component_id, mavlink
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_fsm_tm_t packet_in = {
-        93372036854775807ULL,29,96,163,230,41,108
+        93372036854775807ULL,29,96,163,230,41
     };
     mavlink_fsm_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -1939,7 +1939,6 @@ static void mavlink_test_fsm_tm(uint8_t system_id, uint8_t component_id, mavlink
         packet1.abk_state = packet_in.abk_state;
         packet1.dpl_state = packet_in.dpl_state;
         packet1.fmm_state = packet_in.fmm_state;
-        packet1.fsr_state = packet_in.fsr_state;
         packet1.nas_state = packet_in.nas_state;
         
         
@@ -1955,12 +1954,12 @@ static void mavlink_test_fsm_tm(uint8_t system_id, uint8_t component_id, mavlink
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_fsm_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.fsr_state , packet1.nas_state );
+    mavlink_msg_fsm_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state );
     mavlink_msg_fsm_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_fsm_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.fsr_state , packet1.nas_state );
+    mavlink_msg_fsm_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state );
     mavlink_msg_fsm_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -1973,7 +1972,7 @@ static void mavlink_test_fsm_tm(uint8_t system_id, uint8_t component_id, mavlink
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_fsm_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.fsr_state , packet1.nas_state );
+    mavlink_msg_fsm_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state );
     mavlink_msg_fsm_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2200,7 +2199,7 @@ static void mavlink_test_ada_tm(uint8_t system_id, uint8_t component_id, mavlink
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_ada_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,149
+        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,161
     };
     mavlink_ada_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -2215,6 +2214,7 @@ static void mavlink_test_ada_tm(uint8_t system_id, uint8_t component_id, mavlink
         packet1.ref_temperature = packet_in.ref_temperature;
         packet1.msl_pressure = packet_in.msl_pressure;
         packet1.msl_temperature = packet_in.msl_temperature;
+        packet1.dpl_altitude = packet_in.dpl_altitude;
         packet1.state = packet_in.state;
         
         
@@ -2230,12 +2230,12 @@ static void mavlink_test_ada_tm(uint8_t system_id, uint8_t component_id, mavlink
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_ada_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature );
+    mavlink_msg_ada_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature , packet1.dpl_altitude );
     mavlink_msg_ada_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_ada_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature );
+    mavlink_msg_ada_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature , packet1.dpl_altitude );
     mavlink_msg_ada_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2248,7 +2248,7 @@ static void mavlink_test_ada_tm(uint8_t system_id, uint8_t component_id, mavlink
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_ada_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature );
+    mavlink_msg_ada_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature , packet1.dpl_altitude );
     mavlink_msg_ada_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2335,71 +2335,6 @@ static void mavlink_test_nas_tm(uint8_t system_id, uint8_t component_id, mavlink
 #endif
 }
 
-static void mavlink_test_can_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
-    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
-        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAN_TM >= 256) {
-            return;
-        }
-#endif
-    mavlink_message_t msg;
-        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
-        uint16_t i;
-    mavlink_can_tm_t packet_in = {
-        93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,18483,18587,89,156
-    };
-    mavlink_can_tm_t packet1, packet2;
-        memset(&packet1, 0, sizeof(packet1));
-        packet1.timestamp = packet_in.timestamp;
-        packet1.last_sent_ts = packet_in.last_sent_ts;
-        packet1.last_rcv_ts = packet_in.last_rcv_ts;
-        packet1.n_sent = packet_in.n_sent;
-        packet1.n_rcv = packet_in.n_rcv;
-        packet1.last_sent = packet_in.last_sent;
-        packet1.last_rcv = packet_in.last_rcv;
-        
-        
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
-        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
-           // cope with extensions
-           memset(MAVLINK_MSG_ID_CAN_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAN_TM_MIN_LEN);
-        }
-#endif
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_can_tm_encode(system_id, component_id, &msg, &packet1);
-    mavlink_msg_can_tm_decode(&msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_can_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.n_sent , packet1.n_rcv , packet1.last_sent , packet1.last_rcv , packet1.last_sent_ts , packet1.last_rcv_ts );
-    mavlink_msg_can_tm_decode(&msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_can_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.n_sent , packet1.n_rcv , packet1.last_sent , packet1.last_rcv , packet1.last_sent_ts , packet1.last_rcv_ts );
-    mavlink_msg_can_tm_decode(&msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-        memset(&packet2, 0, sizeof(packet2));
-        mavlink_msg_to_send_buffer(buffer, &msg);
-        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
-            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
-        }
-    mavlink_msg_can_tm_decode(last_msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-        
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_can_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.n_sent , packet1.n_rcv , packet1.last_sent , packet1.last_rcv , packet1.last_sent_ts , packet1.last_rcv_ts );
-    mavlink_msg_can_tm_decode(last_msg, &packet2);
-        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
-    MAVLINK_ASSERT(mavlink_get_message_info_by_name("CAN_TM") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_CAN_TM) != NULL);
-#endif
-}
-
 static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -2412,7 +2347,7 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_rocket_flight_tm_t packet_in = {
-        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,205,16,83,150,217,28,95,162,229,40,107
+        93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,217,28,95,162,229,40,107,174,241,52,119
     };
     mavlink_rocket_flight_tm_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -2438,6 +2373,7 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i
         packet1.gps_alt = packet_in.gps_alt;
         packet1.abk_angle = packet_in.abk_angle;
         packet1.abk_estimated_cd = packet_in.abk_estimated_cd;
+        packet1.parachute_load = packet_in.parachute_load;
         packet1.nas_n = packet_in.nas_n;
         packet1.nas_e = packet_in.nas_e;
         packet1.nas_d = packet_in.nas_d;
@@ -2478,12 +2414,12 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_rocket_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.abk_estimated_cd , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.vbat , packet1.temperature , packet1.logger_error );
+    mavlink_msg_rocket_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.abk_estimated_cd , packet1.parachute_load , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.vbat , packet1.temperature , packet1.logger_error );
     mavlink_msg_rocket_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.abk_estimated_cd , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.vbat , packet1.temperature , packet1.logger_error );
+    mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.abk_estimated_cd , packet1.parachute_load , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.vbat , packet1.temperature , packet1.logger_error );
     mavlink_msg_rocket_flight_tm_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2496,7 +2432,7 @@ static void mavlink_test_rocket_flight_tm(uint8_t system_id, uint8_t component_i
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_rocket_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.abk_estimated_cd , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.vbat , packet1.temperature , packet1.logger_error );
+    mavlink_msg_rocket_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.abk_estimated_cd , packet1.parachute_load , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.vbat , packet1.temperature , packet1.logger_error );
     mavlink_msg_rocket_flight_tm_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -2795,7 +2731,6 @@ static void mavlink_test_pyxis(uint8_t system_id, uint8_t component_id, mavlink_
     mavlink_test_task_stats_tm(system_id, component_id, last_msg);
     mavlink_test_ada_tm(system_id, component_id, last_msg);
     mavlink_test_nas_tm(system_id, component_id, last_msg);
-    mavlink_test_can_tm(system_id, component_id, last_msg);
     mavlink_test_rocket_flight_tm(system_id, component_id, last_msg);
     mavlink_test_payload_flight_tm(system_id, component_id, last_msg);
     mavlink_test_rocket_stats_tm(system_id, component_id, last_msg);
diff --git a/mavlink_lib/pyxis/version.h b/mavlink_lib/pyxis/version.h
index ce1282ebdeffbe7430bdd3de7b6fccc7669f70c4..632d59dd234e5566f469090a1d1df0032ed63ab5 100644
--- a/mavlink_lib/pyxis/version.h
+++ b/mavlink_lib/pyxis/version.h
@@ -7,8 +7,8 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Thu Sep 08 2022"
+#define MAVLINK_BUILD_DATE "Sat Sep 10 2022"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 163
+#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 167
  
 #endif // MAVLINK_VERSION_H
diff --git a/message_definitions/pyxis.xml b/message_definitions/pyxis.xml
index 2998122bec75975d63d84f4ef93383d56ecab044..2802d9115adc4c3ffdb51d1be2d64ffc3f26656e 100644
--- a/message_definitions/pyxis.xml
+++ b/message_definitions/pyxis.xml
@@ -348,14 +348,12 @@
             <field name="board_scheduler" type="uint8_t">True if the board scheduler is running</field>
         </message>
         <message id="201" name="FSM_TM">
-            <!-- SAME FOR ROCKET AND PAYLOAD BUT ONE SET SHOULD CONTAIN THE OTHER -->
             <description>Flight State Machine status telemetry</description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp</field>
             <field name="ada_state" type="uint8_t">Apogee Detection Algorithm state</field>
             <field name="abk_state" type="uint8_t">Air Brakes state</field>
             <field name="dpl_state" type="uint8_t">Deployment state</field>
             <field name="fmm_state" type="uint8_t">Flight Mode Manager state</field>
-            <field name="fsr_state" type="uint8_t">Flight Stats Recorder state</field>
             <field name="nas_state" type="uint8_t">Navigation and Attitude State state</field>
         </message>
         <message id="202" name="LOGGER_TM">
@@ -389,7 +387,6 @@
             <field name="packet_rx_drop_count" type="uint16_t">  Number of packet drops   </field>
         </message>
         <message id="204" name="TASK_STATS_TM">
-            <!-- At request we expect n messages as response -->
             <description>Statistics of the Task Scheduler</description>
             <field name="timestamp" type="uint64_t" units="us">When was this logged </field>
             <field name="task_id" type="uint8_t">Task ID</field>
@@ -413,6 +410,7 @@
             <field name="ref_temperature" type="float" units="degC">Calibration temperature</field>
             <field name="msl_pressure" type="float" units="Pa">Expected pressure at mean sea level</field>
             <field name="msl_temperature" type="float" units="degC">Expected temperature at mean sea level</field>
+            <field name="dpl_altitude" type="float" units="m">Main parachute deployment altituyde</field>
         </message>
         <message id="206" name="NAS_TM">
             <description>Navigation System status telemetry</description>
@@ -436,20 +434,8 @@
             <field name="ref_latitude" type="float" units="deg">Calibration latitude</field>
             <field name="ref_longitude" type="float" units="deg">Calibration longitude</field>
         </message>
-        <message id="207" name="CAN_TM">
-            <!-- TODO: UPDATE -->
-            <description>Canbus driver status telemetry</description>
-            <field name="timestamp" type="uint64_t" units="us">When was this logged</field>
-            <field name="n_sent" type="uint16_t">Number of sent messages</field>
-            <field name="n_rcv" type="uint16_t">Number of received messages</field>
-            <field name="last_sent" type="uint8_t">Id of the last sent message</field>
-            <field name="last_rcv" type="uint8_t">Id of the last received message</field>
-            <field name="last_sent_ts" type="uint64_t">Timestamp of the last sent message</field>
-            <field name="last_rcv_ts" type="uint64_t">Timestamp of the last received message</field>
-        </message>
-        <message id="208" name="ROCKET_FLIGHT_TM">
+        <message id="207" name="ROCKET_FLIGHT_TM">
             <description>High Rate Telemetry</description>
-            <!-- TODO: UPDATE AND DISCOVER EVENTUAL FORK BETWEEN LOW FR AND HIGH FR -->
             <field name="timestamp" type="uint64_t" units="us">Timestamp in milliseconds</field>
             <field name="ada_state" type="uint8_t">ADA Controller State</field>
             <field name="fmm_state" type="uint8_t">Flight Mode Manager State</field>
@@ -478,6 +464,7 @@
             <field name="gps_alt" type="float" units="m">GPS Altitude</field>
             <field name="abk_angle" type="float" units="deg">Air Brakes angle</field>
             <field name="abk_estimated_cd" type="float">Estimated drag coefficient</field>
+            <field name="parachute_load" type="float">Parachute load cell value</field>
             <field name="nas_n" type="float" units="deg">Navigation system estimated noth position</field>
             <field name="nas_e" type="float" units="deg">Navigation system estimated east position</field>
             <field name="nas_d" type="float" units="m">Navigation system estimated down position</field>
@@ -499,8 +486,7 @@
             <field name="temperature" type="float" units="degC">Temperature</field>
             <field name="logger_error" type="int8_t">Logger error (0 = no error, -1 otherwise)</field>
         </message>
-        <message id="209" name="PAYLOAD_FLIGHT_TM">
-            <!-- TODO: COULD NEED SOMETHING ABOUT CONTROL ALGORITHM LIKE WING EFFICIENCY AND VELOCITIES DURING DESCENDING -->
+        <message id="208" name="PAYLOAD_FLIGHT_TM">
             <description>High Rate Telemetry</description>
             <field name="timestamp" type="uint64_t" units="us">Timestamp in milliseconds</field>
             <field name="ada_state" type="uint8_t">ADA Controller State</field>
@@ -509,7 +495,7 @@
             <field name="pressure_ada" type="float" units="Pa">Atmospheric pressure estimated by ADA</field>
             <field name="pressure_digi" type="float" units="Pa">Pressure from digital sensor</field>
             <field name="pressure_static" type="float" units="Pa">Pressure from static port</field>
-            <field name="pressure_dpl" type="float" units="Pa">Pressure from deployment vane sensor</field> <!-- TODO: RENAME -->
+            <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>
@@ -540,14 +526,13 @@
             <field name="nas_bias_x" type="float">Navigation system gyroscope bias on x axis</field>
             <field name="nas_bias_y" type="float">Navigation system gyroscope bias on x axis</field>
             <field name="nas_bias_z" type="float">Navigation system gyroscope bias on x axis</field>
-            <!-- TODO: ADD CONTROL ALGORITHM THINGS -->
             <field name="pin_nosecone" type="uint8_t">Nosecone pin status (1 = connected, 0 = disconnected)</field>
             <field name="vbat" type="float" units="V">Battery voltage</field>
-            <field name="vsupply_5v" type="float" units="V">Power supply 5V</field> <!-- MAYBE USEFUL -->
+            <field name="vsupply_5v" type="float" units="V">Power supply 5V</field>
             <field name="temperature" type="float" units="degC">Temperature</field>
             <field name="logger_error" type="int8_t">Logger error (0 = no error)</field>
         </message>
-        <message id="210" name="ROCKET_STATS_TM">
+        <message id="209" name="ROCKET_STATS_TM">
             <description>Low Rate Telemetry</description>
             <field name="liftoff_ts" type="uint64_t" units="us">System clock at liftoff</field>
             <field name="liftoff_max_acc_ts" type="uint64_t" units="us">System clock at the maximum liftoff acceleration</field>
@@ -568,9 +553,8 @@
             <field name="cpu_load" type="float">CPU load in percentage</field>
             <field name="free_heap" type="uint32_t">Amount of available heap in memory</field>
         </message>
-        <message id="211" name="PAYLOAD_STATS_TM">
+        <message id="210" name="PAYLOAD_STATS_TM">
             <description>Low Rate Telemetry</description>
-            <!-- TODO: COULD NEED SOMETHING ABOUT CONTROL ALGORITHM LIKE WING EFFICIENCY AND VELOCITIES DURING DESCENDING -->
             <field name="liftoff_max_acc_ts" type="uint64_t" units="us">System clock at the maximum liftoff acceleration</field>
             <field name="liftoff_max_acc" type="float" units="m/s2">Maximum liftoff acceleration</field>
             <field name="dpl_ts" type="uint64_t" units="us">System clock at drouge deployment</field>