Parcourir la source

增加吊运器姿态四元数发送、增加吊运器安装方向设置、增加吊运器工作状态字段说明

karo lee il y a 2 mois
Parent
commit
354e35bbe0

+ 6 - 3
msg_definitions/VKFly.xml

@@ -802,9 +802,10 @@
         <param index="1" label="Weight Calibrate">NAN means invalid. Other positive value means the
           actual weight</param>
         <param index="2" label="Factory Reset">NAN means invalid. 1 means do factory reset.</param>
-        <param index="3" label=""> </param>
-        <param index="4" label=""> </param>
-        <param index="5" label=""> </param>
+        <param index="3" label="Fuse Break">NAN means invalid. 1 means do eft fuse break.</param>
+        <param index="4" label="Release Hook">NAN mean invalid. 
+        1 means do release hook, 2 means restart hook, 3 means stop </param>
+        <param index="5" label="Weigher Orientation" units="deg" minValue="-180" maxValue="180">NAN mean invalid. </param>
         <param index="6" label=""> </param>
         <param index="7" label=""> </param>
       </entry>
@@ -1139,6 +1140,8 @@
       <field type="uint16_t" name="weight_d">weight variant rate</field>
       <field type="uint8_t" name="work_state"></field>
       <field type="uint8_t" name="err_code"></field>
+      <extensions />
+      <field type="float[4]" name="attitude_Q"></field>
     </message>
 
     <message id="53022" name="VK_PAYLOAD_DATA_RELAY">

+ 12 - 1
readme.md

@@ -856,8 +856,17 @@ comp_id 为 0 时, 飞控将回复多个消息逐个返回所有可获取设备
 | timestamp  | 毫秒时间戳           |
 | weight     | 称重器重量 g         |
 | weight_d   | 称重器重量变化率 g/s |
-| work_state | 工作状态             |
+| work_state | 工作状态 参考work_state说明 |
 | err_code   | 称重器故障码         |
+| attitude_Q | 称重器IMU姿态四元数   |
+
+work_state状态字段位掩码说明:
+
+bit 0-3:IMU 安装方向
+0 - 前向安装
+1 - 右向安装
+2 - 后向安装
+3 - 左向安装
 
 ### 2.25 电调状态数据 VK_DIGI_ESC_STATUS
 
@@ -1672,6 +1681,8 @@ param2 = (float)(颜色 + (闪烁 << 4) +(电调编号<<8))
 | param1 | 重量校准, 填写实际载重单位克. NAN表示忽略 |
 | param2 | 1-恢复出厂配置.  NAN表示忽略              |
 | param3 | 熔断指令,1-进行熔断.  NAN表示忽略        |
+| param4 | 脱钩指令,1-进行脱钩, 2-脱钩重置, 3-停止动作. NAN表示忽略|
+| param5 | 安装方向,-180~180度, NAN表示无效       |
 
 ### 5.37 队形飞行 VKFLY_CMD_FORMATION_FLY
 

Fichier diff supprimé car celui-ci est trop grand
+ 1 - 1
v2.0/VKFly/VKFly.h


+ 1 - 1
v2.0/VKFly/mavlink.h

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH 2989708805911485893
+#define MAVLINK_PRIMARY_XML_HASH -1473904325831651581
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 42 - 24
v2.0/VKFly/mavlink_msg_vk_weigher_state.h

@@ -10,39 +10,42 @@ typedef struct __mavlink_vk_weigher_state_t {
  uint16_t weight_d; /*<  weight variant rate*/
  uint8_t work_state; /*<  */
  uint8_t err_code; /*<  */
+ float attitude_Q[4]; /*<  */
 } mavlink_vk_weigher_state_t;
 
-#define MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN 12
+#define MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN 28
 #define MAVLINK_MSG_ID_VK_WEIGHER_STATE_MIN_LEN 12
-#define MAVLINK_MSG_ID_53021_LEN 12
+#define MAVLINK_MSG_ID_53021_LEN 28
 #define MAVLINK_MSG_ID_53021_MIN_LEN 12
 
 #define MAVLINK_MSG_ID_VK_WEIGHER_STATE_CRC 89
 #define MAVLINK_MSG_ID_53021_CRC 89
 
-
+#define MAVLINK_MSG_VK_WEIGHER_STATE_FIELD_ATTITUDE_Q_LEN 4
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_VK_WEIGHER_STATE { \
     53021, \
     "VK_WEIGHER_STATE", \
-    5, \
+    6, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_weigher_state_t, timestamp) }, \
          { "weight", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_weigher_state_t, weight) }, \
          { "weight_d", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_vk_weigher_state_t, weight_d) }, \
          { "work_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_vk_weigher_state_t, work_state) }, \
          { "err_code", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_vk_weigher_state_t, err_code) }, \
+         { "attitude_Q", NULL, MAVLINK_TYPE_FLOAT, 4, 12, offsetof(mavlink_vk_weigher_state_t, attitude_Q) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_VK_WEIGHER_STATE { \
     "VK_WEIGHER_STATE", \
-    5, \
+    6, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_weigher_state_t, timestamp) }, \
          { "weight", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_weigher_state_t, weight) }, \
          { "weight_d", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_vk_weigher_state_t, weight_d) }, \
          { "work_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_vk_weigher_state_t, work_state) }, \
          { "err_code", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_vk_weigher_state_t, err_code) }, \
+         { "attitude_Q", NULL, MAVLINK_TYPE_FLOAT, 4, 12, offsetof(mavlink_vk_weigher_state_t, attitude_Q) }, \
          } \
 }
 #endif
@@ -58,10 +61,11 @@ typedef struct __mavlink_vk_weigher_state_t {
  * @param weight_d  weight variant rate
  * @param work_state  
  * @param err_code  
+ * @param attitude_Q  
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_weigher_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint32_t timestamp, uint32_t weight, uint16_t weight_d, uint8_t work_state, uint8_t err_code)
+                               uint32_t timestamp, uint32_t weight, uint16_t weight_d, uint8_t work_state, uint8_t err_code, const float *attitude_Q)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN];
@@ -70,7 +74,7 @@ static inline uint16_t mavlink_msg_vk_weigher_state_pack(uint8_t system_id, uint
     _mav_put_uint16_t(buf, 8, weight_d);
     _mav_put_uint8_t(buf, 10, work_state);
     _mav_put_uint8_t(buf, 11, err_code);
-
+    _mav_put_float_array(buf, 12, attitude_Q, 4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN);
 #else
     mavlink_vk_weigher_state_t packet;
@@ -79,7 +83,7 @@ static inline uint16_t mavlink_msg_vk_weigher_state_pack(uint8_t system_id, uint
     packet.weight_d = weight_d;
     packet.work_state = work_state;
     packet.err_code = err_code;
-
+    mav_array_memcpy(packet.attitude_Q, attitude_Q, sizeof(float)*4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN);
 #endif
 
@@ -99,10 +103,11 @@ static inline uint16_t mavlink_msg_vk_weigher_state_pack(uint8_t system_id, uint
  * @param weight_d  weight variant rate
  * @param work_state  
  * @param err_code  
+ * @param attitude_Q  
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_weigher_state_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
-                               uint32_t timestamp, uint32_t weight, uint16_t weight_d, uint8_t work_state, uint8_t err_code)
+                               uint32_t timestamp, uint32_t weight, uint16_t weight_d, uint8_t work_state, uint8_t err_code, const float *attitude_Q)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN];
@@ -111,7 +116,7 @@ static inline uint16_t mavlink_msg_vk_weigher_state_pack_status(uint8_t system_i
     _mav_put_uint16_t(buf, 8, weight_d);
     _mav_put_uint8_t(buf, 10, work_state);
     _mav_put_uint8_t(buf, 11, err_code);
-
+    _mav_put_float_array(buf, 12, attitude_Q, 4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN);
 #else
     mavlink_vk_weigher_state_t packet;
@@ -120,7 +125,7 @@ static inline uint16_t mavlink_msg_vk_weigher_state_pack_status(uint8_t system_i
     packet.weight_d = weight_d;
     packet.work_state = work_state;
     packet.err_code = err_code;
-
+    mav_array_memcpy(packet.attitude_Q, attitude_Q, sizeof(float)*4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN);
 #endif
 
@@ -143,11 +148,12 @@ static inline uint16_t mavlink_msg_vk_weigher_state_pack_status(uint8_t system_i
  * @param weight_d  weight variant rate
  * @param work_state  
  * @param err_code  
+ * @param attitude_Q  
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_weigher_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint32_t timestamp,uint32_t weight,uint16_t weight_d,uint8_t work_state,uint8_t err_code)
+                                   uint32_t timestamp,uint32_t weight,uint16_t weight_d,uint8_t work_state,uint8_t err_code,const float *attitude_Q)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN];
@@ -156,7 +162,7 @@ static inline uint16_t mavlink_msg_vk_weigher_state_pack_chan(uint8_t system_id,
     _mav_put_uint16_t(buf, 8, weight_d);
     _mav_put_uint8_t(buf, 10, work_state);
     _mav_put_uint8_t(buf, 11, err_code);
-
+    _mav_put_float_array(buf, 12, attitude_Q, 4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN);
 #else
     mavlink_vk_weigher_state_t packet;
@@ -165,7 +171,7 @@ static inline uint16_t mavlink_msg_vk_weigher_state_pack_chan(uint8_t system_id,
     packet.weight_d = weight_d;
     packet.work_state = work_state;
     packet.err_code = err_code;
-
+    mav_array_memcpy(packet.attitude_Q, attitude_Q, sizeof(float)*4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN);
 #endif
 
@@ -183,7 +189,7 @@ static inline uint16_t mavlink_msg_vk_weigher_state_pack_chan(uint8_t system_id,
  */
 static inline uint16_t mavlink_msg_vk_weigher_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_weigher_state_t* vk_weigher_state)
 {
-    return mavlink_msg_vk_weigher_state_pack(system_id, component_id, msg, vk_weigher_state->timestamp, vk_weigher_state->weight, vk_weigher_state->weight_d, vk_weigher_state->work_state, vk_weigher_state->err_code);
+    return mavlink_msg_vk_weigher_state_pack(system_id, component_id, msg, vk_weigher_state->timestamp, vk_weigher_state->weight, vk_weigher_state->weight_d, vk_weigher_state->work_state, vk_weigher_state->err_code, vk_weigher_state->attitude_Q);
 }
 
 /**
@@ -197,7 +203,7 @@ static inline uint16_t mavlink_msg_vk_weigher_state_encode(uint8_t system_id, ui
  */
 static inline uint16_t mavlink_msg_vk_weigher_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_weigher_state_t* vk_weigher_state)
 {
-    return mavlink_msg_vk_weigher_state_pack_chan(system_id, component_id, chan, msg, vk_weigher_state->timestamp, vk_weigher_state->weight, vk_weigher_state->weight_d, vk_weigher_state->work_state, vk_weigher_state->err_code);
+    return mavlink_msg_vk_weigher_state_pack_chan(system_id, component_id, chan, msg, vk_weigher_state->timestamp, vk_weigher_state->weight, vk_weigher_state->weight_d, vk_weigher_state->work_state, vk_weigher_state->err_code, vk_weigher_state->attitude_Q);
 }
 
 /**
@@ -211,7 +217,7 @@ static inline uint16_t mavlink_msg_vk_weigher_state_encode_chan(uint8_t system_i
  */
 static inline uint16_t mavlink_msg_vk_weigher_state_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_weigher_state_t* vk_weigher_state)
 {
-    return mavlink_msg_vk_weigher_state_pack_status(system_id, component_id, _status, msg,  vk_weigher_state->timestamp, vk_weigher_state->weight, vk_weigher_state->weight_d, vk_weigher_state->work_state, vk_weigher_state->err_code);
+    return mavlink_msg_vk_weigher_state_pack_status(system_id, component_id, _status, msg,  vk_weigher_state->timestamp, vk_weigher_state->weight, vk_weigher_state->weight_d, vk_weigher_state->work_state, vk_weigher_state->err_code, vk_weigher_state->attitude_Q);
 }
 
 /**
@@ -223,10 +229,11 @@ static inline uint16_t mavlink_msg_vk_weigher_state_encode_status(uint8_t system
  * @param weight_d  weight variant rate
  * @param work_state  
  * @param err_code  
+ * @param attitude_Q  
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_vk_weigher_state_send(mavlink_channel_t chan, uint32_t timestamp, uint32_t weight, uint16_t weight_d, uint8_t work_state, uint8_t err_code)
+static inline void mavlink_msg_vk_weigher_state_send(mavlink_channel_t chan, uint32_t timestamp, uint32_t weight, uint16_t weight_d, uint8_t work_state, uint8_t err_code, const float *attitude_Q)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN];
@@ -235,7 +242,7 @@ static inline void mavlink_msg_vk_weigher_state_send(mavlink_channel_t chan, uin
     _mav_put_uint16_t(buf, 8, weight_d);
     _mav_put_uint8_t(buf, 10, work_state);
     _mav_put_uint8_t(buf, 11, err_code);
-
+    _mav_put_float_array(buf, 12, attitude_Q, 4);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_WEIGHER_STATE, buf, MAVLINK_MSG_ID_VK_WEIGHER_STATE_MIN_LEN, MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN, MAVLINK_MSG_ID_VK_WEIGHER_STATE_CRC);
 #else
     mavlink_vk_weigher_state_t packet;
@@ -244,7 +251,7 @@ static inline void mavlink_msg_vk_weigher_state_send(mavlink_channel_t chan, uin
     packet.weight_d = weight_d;
     packet.work_state = work_state;
     packet.err_code = err_code;
-
+    mav_array_memcpy(packet.attitude_Q, attitude_Q, sizeof(float)*4);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_WEIGHER_STATE, (const char *)&packet, MAVLINK_MSG_ID_VK_WEIGHER_STATE_MIN_LEN, MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN, MAVLINK_MSG_ID_VK_WEIGHER_STATE_CRC);
 #endif
 }
@@ -257,7 +264,7 @@ static inline void mavlink_msg_vk_weigher_state_send(mavlink_channel_t chan, uin
 static inline void mavlink_msg_vk_weigher_state_send_struct(mavlink_channel_t chan, const mavlink_vk_weigher_state_t* vk_weigher_state)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_vk_weigher_state_send(chan, vk_weigher_state->timestamp, vk_weigher_state->weight, vk_weigher_state->weight_d, vk_weigher_state->work_state, vk_weigher_state->err_code);
+    mavlink_msg_vk_weigher_state_send(chan, vk_weigher_state->timestamp, vk_weigher_state->weight, vk_weigher_state->weight_d, vk_weigher_state->work_state, vk_weigher_state->err_code, vk_weigher_state->attitude_Q);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_WEIGHER_STATE, (const char *)vk_weigher_state, MAVLINK_MSG_ID_VK_WEIGHER_STATE_MIN_LEN, MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN, MAVLINK_MSG_ID_VK_WEIGHER_STATE_CRC);
 #endif
@@ -271,7 +278,7 @@ static inline void mavlink_msg_vk_weigher_state_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_vk_weigher_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t timestamp, uint32_t weight, uint16_t weight_d, uint8_t work_state, uint8_t err_code)
+static inline void mavlink_msg_vk_weigher_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t timestamp, uint32_t weight, uint16_t weight_d, uint8_t work_state, uint8_t err_code, const float *attitude_Q)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -280,7 +287,7 @@ static inline void mavlink_msg_vk_weigher_state_send_buf(mavlink_message_t *msgb
     _mav_put_uint16_t(buf, 8, weight_d);
     _mav_put_uint8_t(buf, 10, work_state);
     _mav_put_uint8_t(buf, 11, err_code);
-
+    _mav_put_float_array(buf, 12, attitude_Q, 4);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_WEIGHER_STATE, buf, MAVLINK_MSG_ID_VK_WEIGHER_STATE_MIN_LEN, MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN, MAVLINK_MSG_ID_VK_WEIGHER_STATE_CRC);
 #else
     mavlink_vk_weigher_state_t *packet = (mavlink_vk_weigher_state_t *)msgbuf;
@@ -289,7 +296,7 @@ static inline void mavlink_msg_vk_weigher_state_send_buf(mavlink_message_t *msgb
     packet->weight_d = weight_d;
     packet->work_state = work_state;
     packet->err_code = err_code;
-
+    mav_array_memcpy(packet->attitude_Q, attitude_Q, sizeof(float)*4);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_WEIGHER_STATE, (const char *)packet, MAVLINK_MSG_ID_VK_WEIGHER_STATE_MIN_LEN, MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN, MAVLINK_MSG_ID_VK_WEIGHER_STATE_CRC);
 #endif
 }
@@ -350,6 +357,16 @@ static inline uint8_t mavlink_msg_vk_weigher_state_get_err_code(const mavlink_me
     return _MAV_RETURN_uint8_t(msg,  11);
 }
 
+/**
+ * @brief Get field attitude_Q from vk_weigher_state message
+ *
+ * @return  
+ */
+static inline uint16_t mavlink_msg_vk_weigher_state_get_attitude_Q(const mavlink_message_t* msg, float *attitude_Q)
+{
+    return _MAV_RETURN_float_array(msg, attitude_Q, 4,  12);
+}
+
 /**
  * @brief Decode a vk_weigher_state message into a struct
  *
@@ -364,6 +381,7 @@ static inline void mavlink_msg_vk_weigher_state_decode(const mavlink_message_t*
     vk_weigher_state->weight_d = mavlink_msg_vk_weigher_state_get_weight_d(msg);
     vk_weigher_state->work_state = mavlink_msg_vk_weigher_state_get_work_state(msg);
     vk_weigher_state->err_code = mavlink_msg_vk_weigher_state_get_err_code(msg);
+    mavlink_msg_vk_weigher_state_get_attitude_Q(msg, vk_weigher_state->attitude_Q);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN? msg->len : MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN;
         memset(vk_weigher_state, 0, MAVLINK_MSG_ID_VK_WEIGHER_STATE_LEN);

+ 5 - 4
v2.0/VKFly/testsuite.h

@@ -985,7 +985,7 @@ static void mavlink_test_vk_weigher_state(uint8_t system_id, uint8_t component_i
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_vk_weigher_state_t packet_in = {
-        963497464,963497672,17651,163,230
+        963497464,963497672,17651,163,230,{ 101.0, 102.0, 103.0, 104.0 }
     };
     mavlink_vk_weigher_state_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -995,6 +995,7 @@ static void mavlink_test_vk_weigher_state(uint8_t system_id, uint8_t component_i
         packet1.work_state = packet_in.work_state;
         packet1.err_code = packet_in.err_code;
         
+        mav_array_memcpy(packet1.attitude_Q, packet_in.attitude_Q, sizeof(float)*4);
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
         if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
@@ -1008,12 +1009,12 @@ static void mavlink_test_vk_weigher_state(uint8_t system_id, uint8_t component_i
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_weigher_state_pack(system_id, component_id, &msg , packet1.timestamp , packet1.weight , packet1.weight_d , packet1.work_state , packet1.err_code );
+    mavlink_msg_vk_weigher_state_pack(system_id, component_id, &msg , packet1.timestamp , packet1.weight , packet1.weight_d , packet1.work_state , packet1.err_code , packet1.attitude_Q );
     mavlink_msg_vk_weigher_state_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_weigher_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.weight , packet1.weight_d , packet1.work_state , packet1.err_code );
+    mavlink_msg_vk_weigher_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.weight , packet1.weight_d , packet1.work_state , packet1.err_code , packet1.attitude_Q );
     mavlink_msg_vk_weigher_state_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -1026,7 +1027,7 @@ static void mavlink_test_vk_weigher_state(uint8_t system_id, uint8_t component_i
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_weigher_state_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.weight , packet1.weight_d , packet1.work_state , packet1.err_code );
+    mavlink_msg_vk_weigher_state_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.weight , packet1.weight_d , packet1.work_state , packet1.err_code , packet1.attitude_Q );
     mavlink_msg_vk_weigher_state_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 

+ 1 - 1
v2.0/VKFly/version.h

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Dec 30 2025"
+#define MAVLINK_BUILD_DATE "Mon Feb 02 2026"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
  

+ 1 - 1
v2.0/common/common.h

@@ -10,7 +10,7 @@
     #error Wrong include order: MAVLINK_COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
 #endif
 
-#define MAVLINK_COMMON_XML_HASH -753897379657521811
+#define MAVLINK_COMMON_XML_HASH -3706868761101684576
 
 #ifdef __cplusplus
 extern "C" {

+ 1 - 1
v2.0/common/mavlink.h

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -753897379657521811
+#define MAVLINK_PRIMARY_XML_HASH -3706868761101684576
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 1 - 1
v2.0/common/version.h

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Dec 30 2025"
+#define MAVLINK_BUILD_DATE "Mon Feb 02 2026"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
  

+ 1 - 1
v2.0/minimal/mavlink.h

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH 6588211659819560145
+#define MAVLINK_PRIMARY_XML_HASH -3071747296240045658
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 1 - 1
v2.0/minimal/minimal.h

@@ -10,7 +10,7 @@
     #error Wrong include order: MAVLINK_MINIMAL.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
 #endif
 
-#define MAVLINK_MINIMAL_XML_HASH 6588211659819560145
+#define MAVLINK_MINIMAL_XML_HASH -3071747296240045658
 
 #ifdef __cplusplus
 extern "C" {

+ 1 - 1
v2.0/minimal/version.h

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Dec 30 2025"
+#define MAVLINK_BUILD_DATE "Mon Feb 02 2026"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
  

+ 1 - 1
v2.0/standard/mavlink.h

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -3174030842127723093
+#define MAVLINK_PRIMARY_XML_HASH 8181879447612882476
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 1 - 1
v2.0/standard/standard.h

@@ -10,7 +10,7 @@
     #error Wrong include order: MAVLINK_STANDARD.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
 #endif
 
-#define MAVLINK_STANDARD_XML_HASH -3174030842127723093
+#define MAVLINK_STANDARD_XML_HASH 8181879447612882476
 
 #ifdef __cplusplus
 extern "C" {

+ 1 - 1
v2.0/standard/version.h

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Dec 30 2025"
+#define MAVLINK_BUILD_DATE "Mon Feb 02 2026"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
  

Certains fichiers n'ont pas été affichés car il y a eu trop de fichiers modifiés dans ce diff