Browse Source

增加天渠舵机状态

LiuYang 1 month ago
parent
commit
d7e29d9275

+ 2 - 1
msg_definitions/VKFly.xml

@@ -1172,7 +1172,8 @@
     </message>
 
     <message id="53030" name="VKFLY_TIANQU_SERVO_STATUS">
-      <description>EDU status ack</description>
+      <description>TianQu servo status</description>
+      <field type="uint32_t" name="timestamp"></field>
       <field type="uint32_t" name="load_status"></field>
       <field type="uint32_t" name="servo_status"></field>
     </message>

File diff suppressed because it is too large
+ 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 4356456235361243861
+#define MAVLINK_PRIMARY_XML_HASH -8555412987721132201
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 61 - 33
v2.0/VKFly/mavlink_msg_vkfly_tianqu_servo_status.h

@@ -5,17 +5,18 @@
 
 
 typedef struct __mavlink_vkfly_tianqu_servo_status_t {
+ uint32_t timestamp; /*<  */
  uint32_t load_status; /*<  */
  uint32_t servo_status; /*<  */
 } mavlink_vkfly_tianqu_servo_status_t;
 
-#define MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_LEN 8
-#define MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_MIN_LEN 8
-#define MAVLINK_MSG_ID_53030_LEN 8
-#define MAVLINK_MSG_ID_53030_MIN_LEN 8
+#define MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_LEN 12
+#define MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_MIN_LEN 12
+#define MAVLINK_MSG_ID_53030_LEN 12
+#define MAVLINK_MSG_ID_53030_MIN_LEN 12
 
-#define MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_CRC 157
-#define MAVLINK_MSG_ID_53030_CRC 157
+#define MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_CRC 148
+#define MAVLINK_MSG_ID_53030_CRC 148
 
 
 
@@ -23,17 +24,19 @@ typedef struct __mavlink_vkfly_tianqu_servo_status_t {
 #define MAVLINK_MESSAGE_INFO_VKFLY_TIANQU_SERVO_STATUS { \
     53030, \
     "VKFLY_TIANQU_SERVO_STATUS", \
-    2, \
-    {  { "load_status", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vkfly_tianqu_servo_status_t, load_status) }, \
-         { "servo_status", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vkfly_tianqu_servo_status_t, servo_status) }, \
+    3, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vkfly_tianqu_servo_status_t, timestamp) }, \
+         { "load_status", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vkfly_tianqu_servo_status_t, load_status) }, \
+         { "servo_status", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_vkfly_tianqu_servo_status_t, servo_status) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_VKFLY_TIANQU_SERVO_STATUS { \
     "VKFLY_TIANQU_SERVO_STATUS", \
-    2, \
-    {  { "load_status", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vkfly_tianqu_servo_status_t, load_status) }, \
-         { "servo_status", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vkfly_tianqu_servo_status_t, servo_status) }, \
+    3, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vkfly_tianqu_servo_status_t, timestamp) }, \
+         { "load_status", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vkfly_tianqu_servo_status_t, load_status) }, \
+         { "servo_status", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_vkfly_tianqu_servo_status_t, servo_status) }, \
          } \
 }
 #endif
@@ -44,21 +47,24 @@ typedef struct __mavlink_vkfly_tianqu_servo_status_t {
  * @param component_id ID of this component (e.g. 200 for IMU)
  * @param msg The MAVLink message to compress the data into
  *
+ * @param timestamp  
  * @param load_status  
  * @param servo_status  
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vkfly_tianqu_servo_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint32_t load_status, uint32_t servo_status)
+                               uint32_t timestamp, uint32_t load_status, uint32_t servo_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_LEN];
-    _mav_put_uint32_t(buf, 0, load_status);
-    _mav_put_uint32_t(buf, 4, servo_status);
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, load_status);
+    _mav_put_uint32_t(buf, 8, servo_status);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_LEN);
 #else
     mavlink_vkfly_tianqu_servo_status_t packet;
+    packet.timestamp = timestamp;
     packet.load_status = load_status;
     packet.servo_status = servo_status;
 
@@ -76,21 +82,24 @@ static inline uint16_t mavlink_msg_vkfly_tianqu_servo_status_pack(uint8_t system
  * @param status MAVLink status structure
  * @param msg The MAVLink message to compress the data into
  *
+ * @param timestamp  
  * @param load_status  
  * @param servo_status  
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vkfly_tianqu_servo_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
-                               uint32_t load_status, uint32_t servo_status)
+                               uint32_t timestamp, uint32_t load_status, uint32_t servo_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_LEN];
-    _mav_put_uint32_t(buf, 0, load_status);
-    _mav_put_uint32_t(buf, 4, servo_status);
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, load_status);
+    _mav_put_uint32_t(buf, 8, servo_status);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_LEN);
 #else
     mavlink_vkfly_tianqu_servo_status_t packet;
+    packet.timestamp = timestamp;
     packet.load_status = load_status;
     packet.servo_status = servo_status;
 
@@ -111,22 +120,25 @@ static inline uint16_t mavlink_msg_vkfly_tianqu_servo_status_pack_status(uint8_t
  * @param component_id ID of this component (e.g. 200 for IMU)
  * @param chan The MAVLink channel this message will be sent over
  * @param msg The MAVLink message to compress the data into
+ * @param timestamp  
  * @param load_status  
  * @param servo_status  
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vkfly_tianqu_servo_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint32_t load_status,uint32_t servo_status)
+                                   uint32_t timestamp,uint32_t load_status,uint32_t servo_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_LEN];
-    _mav_put_uint32_t(buf, 0, load_status);
-    _mav_put_uint32_t(buf, 4, servo_status);
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, load_status);
+    _mav_put_uint32_t(buf, 8, servo_status);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_LEN);
 #else
     mavlink_vkfly_tianqu_servo_status_t packet;
+    packet.timestamp = timestamp;
     packet.load_status = load_status;
     packet.servo_status = servo_status;
 
@@ -147,7 +159,7 @@ static inline uint16_t mavlink_msg_vkfly_tianqu_servo_status_pack_chan(uint8_t s
  */
 static inline uint16_t mavlink_msg_vkfly_tianqu_servo_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vkfly_tianqu_servo_status_t* vkfly_tianqu_servo_status)
 {
-    return mavlink_msg_vkfly_tianqu_servo_status_pack(system_id, component_id, msg, vkfly_tianqu_servo_status->load_status, vkfly_tianqu_servo_status->servo_status);
+    return mavlink_msg_vkfly_tianqu_servo_status_pack(system_id, component_id, msg, vkfly_tianqu_servo_status->timestamp, vkfly_tianqu_servo_status->load_status, vkfly_tianqu_servo_status->servo_status);
 }
 
 /**
@@ -161,7 +173,7 @@ static inline uint16_t mavlink_msg_vkfly_tianqu_servo_status_encode(uint8_t syst
  */
 static inline uint16_t mavlink_msg_vkfly_tianqu_servo_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vkfly_tianqu_servo_status_t* vkfly_tianqu_servo_status)
 {
-    return mavlink_msg_vkfly_tianqu_servo_status_pack_chan(system_id, component_id, chan, msg, vkfly_tianqu_servo_status->load_status, vkfly_tianqu_servo_status->servo_status);
+    return mavlink_msg_vkfly_tianqu_servo_status_pack_chan(system_id, component_id, chan, msg, vkfly_tianqu_servo_status->timestamp, vkfly_tianqu_servo_status->load_status, vkfly_tianqu_servo_status->servo_status);
 }
 
 /**
@@ -175,28 +187,31 @@ static inline uint16_t mavlink_msg_vkfly_tianqu_servo_status_encode_chan(uint8_t
  */
 static inline uint16_t mavlink_msg_vkfly_tianqu_servo_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vkfly_tianqu_servo_status_t* vkfly_tianqu_servo_status)
 {
-    return mavlink_msg_vkfly_tianqu_servo_status_pack_status(system_id, component_id, _status, msg,  vkfly_tianqu_servo_status->load_status, vkfly_tianqu_servo_status->servo_status);
+    return mavlink_msg_vkfly_tianqu_servo_status_pack_status(system_id, component_id, _status, msg,  vkfly_tianqu_servo_status->timestamp, vkfly_tianqu_servo_status->load_status, vkfly_tianqu_servo_status->servo_status);
 }
 
 /**
  * @brief Send a vkfly_tianqu_servo_status message
  * @param chan MAVLink channel to send the message
  *
+ * @param timestamp  
  * @param load_status  
  * @param servo_status  
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_vkfly_tianqu_servo_status_send(mavlink_channel_t chan, uint32_t load_status, uint32_t servo_status)
+static inline void mavlink_msg_vkfly_tianqu_servo_status_send(mavlink_channel_t chan, uint32_t timestamp, uint32_t load_status, uint32_t servo_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_LEN];
-    _mav_put_uint32_t(buf, 0, load_status);
-    _mav_put_uint32_t(buf, 4, servo_status);
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, load_status);
+    _mav_put_uint32_t(buf, 8, servo_status);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS, buf, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_LEN, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_CRC);
 #else
     mavlink_vkfly_tianqu_servo_status_t packet;
+    packet.timestamp = timestamp;
     packet.load_status = load_status;
     packet.servo_status = servo_status;
 
@@ -212,7 +227,7 @@ static inline void mavlink_msg_vkfly_tianqu_servo_status_send(mavlink_channel_t
 static inline void mavlink_msg_vkfly_tianqu_servo_status_send_struct(mavlink_channel_t chan, const mavlink_vkfly_tianqu_servo_status_t* vkfly_tianqu_servo_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_vkfly_tianqu_servo_status_send(chan, vkfly_tianqu_servo_status->load_status, vkfly_tianqu_servo_status->servo_status);
+    mavlink_msg_vkfly_tianqu_servo_status_send(chan, vkfly_tianqu_servo_status->timestamp, vkfly_tianqu_servo_status->load_status, vkfly_tianqu_servo_status->servo_status);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS, (const char *)vkfly_tianqu_servo_status, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_LEN, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_CRC);
 #endif
@@ -226,16 +241,18 @@ static inline void mavlink_msg_vkfly_tianqu_servo_status_send_struct(mavlink_cha
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_vkfly_tianqu_servo_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t load_status, uint32_t servo_status)
+static inline void mavlink_msg_vkfly_tianqu_servo_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t timestamp, uint32_t load_status, uint32_t servo_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
-    _mav_put_uint32_t(buf, 0, load_status);
-    _mav_put_uint32_t(buf, 4, servo_status);
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, load_status);
+    _mav_put_uint32_t(buf, 8, servo_status);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS, buf, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_LEN, MAVLINK_MSG_ID_VKFLY_TIANQU_SERVO_STATUS_CRC);
 #else
     mavlink_vkfly_tianqu_servo_status_t *packet = (mavlink_vkfly_tianqu_servo_status_t *)msgbuf;
+    packet->timestamp = timestamp;
     packet->load_status = load_status;
     packet->servo_status = servo_status;
 
@@ -249,6 +266,16 @@ static inline void mavlink_msg_vkfly_tianqu_servo_status_send_buf(mavlink_messag
 // MESSAGE VKFLY_TIANQU_SERVO_STATUS UNPACKING
 
 
+/**
+ * @brief Get field timestamp from vkfly_tianqu_servo_status message
+ *
+ * @return  
+ */
+static inline uint32_t mavlink_msg_vkfly_tianqu_servo_status_get_timestamp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
 /**
  * @brief Get field load_status from vkfly_tianqu_servo_status message
  *
@@ -256,7 +283,7 @@ static inline void mavlink_msg_vkfly_tianqu_servo_status_send_buf(mavlink_messag
  */
 static inline uint32_t mavlink_msg_vkfly_tianqu_servo_status_get_load_status(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint32_t(msg,  0);
+    return _MAV_RETURN_uint32_t(msg,  4);
 }
 
 /**
@@ -266,7 +293,7 @@ static inline uint32_t mavlink_msg_vkfly_tianqu_servo_status_get_load_status(con
  */
 static inline uint32_t mavlink_msg_vkfly_tianqu_servo_status_get_servo_status(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint32_t(msg,  4);
+    return _MAV_RETURN_uint32_t(msg,  8);
 }
 
 /**
@@ -278,6 +305,7 @@ static inline uint32_t mavlink_msg_vkfly_tianqu_servo_status_get_servo_status(co
 static inline void mavlink_msg_vkfly_tianqu_servo_status_decode(const mavlink_message_t* msg, mavlink_vkfly_tianqu_servo_status_t* vkfly_tianqu_servo_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    vkfly_tianqu_servo_status->timestamp = mavlink_msg_vkfly_tianqu_servo_status_get_timestamp(msg);
     vkfly_tianqu_servo_status->load_status = mavlink_msg_vkfly_tianqu_servo_status_get_load_status(msg);
     vkfly_tianqu_servo_status->servo_status = mavlink_msg_vkfly_tianqu_servo_status_get_servo_status(msg);
 #else

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

@@ -1337,10 +1337,11 @@ static void mavlink_test_vkfly_tianqu_servo_status(uint8_t system_id, uint8_t co
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_vkfly_tianqu_servo_status_t packet_in = {
-        963497464,963497672
+        963497464,963497672,963497880
     };
     mavlink_vkfly_tianqu_servo_status_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
+        packet1.timestamp = packet_in.timestamp;
         packet1.load_status = packet_in.load_status;
         packet1.servo_status = packet_in.servo_status;
         
@@ -1357,12 +1358,12 @@ static void mavlink_test_vkfly_tianqu_servo_status(uint8_t system_id, uint8_t co
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vkfly_tianqu_servo_status_pack(system_id, component_id, &msg , packet1.load_status , packet1.servo_status );
+    mavlink_msg_vkfly_tianqu_servo_status_pack(system_id, component_id, &msg , packet1.timestamp , packet1.load_status , packet1.servo_status );
     mavlink_msg_vkfly_tianqu_servo_status_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vkfly_tianqu_servo_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.load_status , packet1.servo_status );
+    mavlink_msg_vkfly_tianqu_servo_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.load_status , packet1.servo_status );
     mavlink_msg_vkfly_tianqu_servo_status_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -1375,7 +1376,7 @@ static void mavlink_test_vkfly_tianqu_servo_status(uint8_t system_id, uint8_t co
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vkfly_tianqu_servo_status_send(MAVLINK_COMM_1 , packet1.load_status , packet1.servo_status );
+    mavlink_msg_vkfly_tianqu_servo_status_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.load_status , packet1.servo_status );
     mavlink_msg_vkfly_tianqu_servo_status_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 

+ 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 5984965082876208430
+#define MAVLINK_COMMON_XML_HASH 5381913627461025617
 
 #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 5984965082876208430
+#define MAVLINK_PRIMARY_XML_HASH 5381913627461025617
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -5510348078676338365
+#define MAVLINK_PRIMARY_XML_HASH 1239447294807396289
 
 #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 -5510348078676338365
+#define MAVLINK_MINIMAL_XML_HASH 1239447294807396289
 
 #ifdef __cplusplus
 extern "C" {

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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH 4898782093141634418
+#define MAVLINK_PRIMARY_XML_HASH -5456636731413327166
 
 #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 4898782093141634418
+#define MAVLINK_STANDARD_XML_HASH -5456636731413327166
 
 #ifdef __cplusplus
 extern "C" {

Some files were not shown because too many files changed in this diff