Procházet zdrojové kódy

修改 VK_ENGINE_ECU_STAUS 消息

Liu Yang před 2 dny
rodič
revize
94b874cce2

+ 13 - 6
msg_definitions/VKFly.xml

@@ -806,9 +806,10 @@
           actual weight</param>
         <param index="2" label="Factory Reset">NAN means invalid. 1 means do factory reset.</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="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>
@@ -922,7 +923,8 @@
       <entry value="44073" name="VKFLY_CMD_CLEAR_SERVO_DISPALY" hasLocation="false"
         isDestination="false">
         <description>Vehicle act</description>
-        <param index="1" label="clear dispaly" minValue="0" maxValue="1">NAN means ignore. 1 means clear servo status dispaly</param>
+        <param index="1" label="clear dispaly" minValue="0" maxValue="1">NAN means ignore. 1 means
+          clear servo status dispaly</param>
         <param index="2" label=""></param>
         <param index="3" label=""></param>
         <param index="4" label=""></param>
@@ -971,7 +973,7 @@
       <field type="uint32_t" name="dist_to_tar" units="cm">distance to target position in cm</field>
       <field type="uint16_t" name="servo_state">bitmap for servo state</field>
       <field type="float" name="flight_dist" units="m">flight distance since this power up</field>
-    <extensions />
+      <extensions />
       <field type="uint16_t" name="servo_display">bitmap for servo state display</field>
     </message>
 
@@ -1046,6 +1048,11 @@
       <field type="uint8_t" name="engine_state">engine state</field>
       <field type="uint8_t" name="index" minValue="0" maxValue="128" increment="1">engine index</field>
       <field type="uint8_t[4]" name="reserve">engine state</field>
+      <extensions />
+      <field type="uint16_t" name="inlet_pressure" units="hPa">inlet air pressure</field>
+      <field type="int16_t" name="ge_temp" units="degC">Ge temperature</field>
+      <field type="int16_t" name="temp_1" units="degC">Ge temperature</field>
+      <field type="int16_t" name="volt_2" units="dV">Ge temperature</field>
     </message>
 
     <message id="53006" name="VK_COMP_VERSION">
@@ -1347,4 +1354,4 @@
 
   </messages>
 
-</mavlink>
+</mavlink>

+ 4 - 0
readme.md

@@ -763,6 +763,10 @@ M5~M8\M13~M16为固定翼舵面舵机.
 | output_curr    | 输出电流 0.1A                     |
 | fault          | 故障字, 参考 VK发动机CAN协议      |
 | engine_state   | 工作状态 0-未启动 1\2-运行 3-锁机 |
+| inlet_pressure | 进气压力 0.1Kpa                   |
+| ge_temp        | 发电机温度 degC                   |
+| temp_1         | 温度1 degC (控制器温度)           |
+| volt_2         | 电压2 0.1V (ECU电压)              |
 | index          | 发动机编号 0-3                    |
 
 转速 RAW_RPM 为飞控自己采集的 HOLL 高低电平转速

Rozdílová data souboru nebyla zobrazena, protože soubor je příliš velký
+ 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 -5628547367346913573
+#define MAVLINK_PRIMARY_XML_HASH -3632216719937891446
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 127 - 15
v2.0/VKFly/mavlink_msg_vk_engine_ecu_staus.h

@@ -3,7 +3,7 @@
 
 #define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS 53005
 
-
+MAVPACKED(
 typedef struct __mavlink_vk_engine_ecu_staus_t {
  uint32_t timestamp; /*< [ms] Timestamp in ms from system boot.*/
  uint32_t total_runtime; /*< [min] range extender output voltage*/
@@ -25,11 +25,15 @@ typedef struct __mavlink_vk_engine_ecu_staus_t {
  uint8_t engine_state; /*<  engine state*/
  uint8_t index; /*<  engine index*/
  uint8_t reserve[4]; /*<  engine state*/
-} mavlink_vk_engine_ecu_staus_t;
+ uint16_t inlet_pressure; /*< [hPa] inlet air pressure*/
+ int16_t ge_temp; /*< [degC] Ge temperature*/
+ int16_t temp_1; /*< [degC] Ge temperature*/
+ int16_t volt_2; /*< [dV] Ge temperature*/
+}) mavlink_vk_engine_ecu_staus_t;
 
-#define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN 37
+#define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN 45
 #define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN 37
-#define MAVLINK_MSG_ID_53005_LEN 37
+#define MAVLINK_MSG_ID_53005_LEN 45
 #define MAVLINK_MSG_ID_53005_MIN_LEN 37
 
 #define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC 145
@@ -41,7 +45,7 @@ typedef struct __mavlink_vk_engine_ecu_staus_t {
 #define MAVLINK_MESSAGE_INFO_VK_ENGINE_ECU_STAUS { \
     53005, \
     "VK_ENGINE_ECU_STAUS", \
-    18, \
+    22, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_engine_ecu_staus_t, timestamp) }, \
          { "spd_rpm", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_vk_engine_ecu_staus_t, spd_rpm) }, \
          { "thr_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_vk_engine_ecu_staus_t, thr_pos) }, \
@@ -60,12 +64,16 @@ typedef struct __mavlink_vk_engine_ecu_staus_t {
          { "engine_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_vk_engine_ecu_staus_t, engine_state) }, \
          { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_vk_engine_ecu_staus_t, index) }, \
          { "reserve", NULL, MAVLINK_TYPE_UINT8_T, 4, 33, offsetof(mavlink_vk_engine_ecu_staus_t, reserve) }, \
+         { "inlet_pressure", NULL, MAVLINK_TYPE_UINT16_T, 0, 37, offsetof(mavlink_vk_engine_ecu_staus_t, inlet_pressure) }, \
+         { "ge_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 39, offsetof(mavlink_vk_engine_ecu_staus_t, ge_temp) }, \
+         { "temp_1", NULL, MAVLINK_TYPE_INT16_T, 0, 41, offsetof(mavlink_vk_engine_ecu_staus_t, temp_1) }, \
+         { "volt_2", NULL, MAVLINK_TYPE_INT16_T, 0, 43, offsetof(mavlink_vk_engine_ecu_staus_t, volt_2) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_VK_ENGINE_ECU_STAUS { \
     "VK_ENGINE_ECU_STAUS", \
-    18, \
+    22, \
     {  { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_engine_ecu_staus_t, timestamp) }, \
          { "spd_rpm", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_vk_engine_ecu_staus_t, spd_rpm) }, \
          { "thr_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_vk_engine_ecu_staus_t, thr_pos) }, \
@@ -84,6 +92,10 @@ typedef struct __mavlink_vk_engine_ecu_staus_t {
          { "engine_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_vk_engine_ecu_staus_t, engine_state) }, \
          { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_vk_engine_ecu_staus_t, index) }, \
          { "reserve", NULL, MAVLINK_TYPE_UINT8_T, 4, 33, offsetof(mavlink_vk_engine_ecu_staus_t, reserve) }, \
+         { "inlet_pressure", NULL, MAVLINK_TYPE_UINT16_T, 0, 37, offsetof(mavlink_vk_engine_ecu_staus_t, inlet_pressure) }, \
+         { "ge_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 39, offsetof(mavlink_vk_engine_ecu_staus_t, ge_temp) }, \
+         { "temp_1", NULL, MAVLINK_TYPE_INT16_T, 0, 41, offsetof(mavlink_vk_engine_ecu_staus_t, temp_1) }, \
+         { "volt_2", NULL, MAVLINK_TYPE_INT16_T, 0, 43, offsetof(mavlink_vk_engine_ecu_staus_t, volt_2) }, \
          } \
 }
 #endif
@@ -114,10 +126,14 @@ typedef struct __mavlink_vk_engine_ecu_staus_t {
  * @param engine_state  engine state
  * @param index  engine index
  * @param reserve  engine state
+ * @param inlet_pressure [hPa] inlet air pressure
+ * @param ge_temp [degC] Ge temperature
+ * @param temp_1 [degC] Ge temperature
+ * @param volt_2 [dV] Ge temperature
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve)
+                               uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve, uint16_t inlet_pressure, int16_t ge_temp, int16_t temp_1, int16_t volt_2)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN];
@@ -138,6 +154,10 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack(uint8_t system_id, u
     _mav_put_uint8_t(buf, 30, fault);
     _mav_put_uint8_t(buf, 31, engine_state);
     _mav_put_uint8_t(buf, 32, index);
+    _mav_put_uint16_t(buf, 37, inlet_pressure);
+    _mav_put_int16_t(buf, 39, ge_temp);
+    _mav_put_int16_t(buf, 41, temp_1);
+    _mav_put_int16_t(buf, 43, volt_2);
     _mav_put_uint8_t_array(buf, 33, reserve, 4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
 #else
@@ -159,6 +179,10 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack(uint8_t system_id, u
     packet.fault = fault;
     packet.engine_state = engine_state;
     packet.index = index;
+    packet.inlet_pressure = inlet_pressure;
+    packet.ge_temp = ge_temp;
+    packet.temp_1 = temp_1;
+    packet.volt_2 = volt_2;
     mav_array_memcpy(packet.reserve, reserve, sizeof(uint8_t)*4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
 #endif
@@ -194,10 +218,14 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack(uint8_t system_id, u
  * @param engine_state  engine state
  * @param index  engine index
  * @param reserve  engine state
+ * @param inlet_pressure [hPa] inlet air pressure
+ * @param ge_temp [degC] Ge temperature
+ * @param temp_1 [degC] Ge temperature
+ * @param volt_2 [dV] Ge temperature
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
-                               uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve)
+                               uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve, uint16_t inlet_pressure, int16_t ge_temp, int16_t temp_1, int16_t volt_2)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN];
@@ -218,6 +246,10 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_status(uint8_t syste
     _mav_put_uint8_t(buf, 30, fault);
     _mav_put_uint8_t(buf, 31, engine_state);
     _mav_put_uint8_t(buf, 32, index);
+    _mav_put_uint16_t(buf, 37, inlet_pressure);
+    _mav_put_int16_t(buf, 39, ge_temp);
+    _mav_put_int16_t(buf, 41, temp_1);
+    _mav_put_int16_t(buf, 43, volt_2);
     _mav_put_uint8_t_array(buf, 33, reserve, 4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
 #else
@@ -239,6 +271,10 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_status(uint8_t syste
     packet.fault = fault;
     packet.engine_state = engine_state;
     packet.index = index;
+    packet.inlet_pressure = inlet_pressure;
+    packet.ge_temp = ge_temp;
+    packet.temp_1 = temp_1;
+    packet.volt_2 = volt_2;
     mav_array_memcpy(packet.reserve, reserve, sizeof(uint8_t)*4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
 #endif
@@ -277,11 +313,15 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_status(uint8_t syste
  * @param engine_state  engine state
  * @param index  engine index
  * @param reserve  engine state
+ * @param inlet_pressure [hPa] inlet air pressure
+ * @param ge_temp [degC] Ge temperature
+ * @param temp_1 [degC] Ge temperature
+ * @param volt_2 [dV] Ge temperature
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint32_t timestamp,uint16_t spd_rpm,uint8_t thr_pos,uint8_t fuel_pos,int16_t cylinderA_temp,int16_t cylinderB_temp,int16_t coolant_temp,uint16_t fuel_remain,uint16_t alarm,uint32_t total_runtime,uint16_t runtime,uint16_t service_time,uint16_t output_volt,uint16_t output_curr,uint8_t fault,uint8_t engine_state,uint8_t index,const uint8_t *reserve)
+                                   uint32_t timestamp,uint16_t spd_rpm,uint8_t thr_pos,uint8_t fuel_pos,int16_t cylinderA_temp,int16_t cylinderB_temp,int16_t coolant_temp,uint16_t fuel_remain,uint16_t alarm,uint32_t total_runtime,uint16_t runtime,uint16_t service_time,uint16_t output_volt,uint16_t output_curr,uint8_t fault,uint8_t engine_state,uint8_t index,const uint8_t *reserve,uint16_t inlet_pressure,int16_t ge_temp,int16_t temp_1,int16_t volt_2)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN];
@@ -302,6 +342,10 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_chan(uint8_t system_
     _mav_put_uint8_t(buf, 30, fault);
     _mav_put_uint8_t(buf, 31, engine_state);
     _mav_put_uint8_t(buf, 32, index);
+    _mav_put_uint16_t(buf, 37, inlet_pressure);
+    _mav_put_int16_t(buf, 39, ge_temp);
+    _mav_put_int16_t(buf, 41, temp_1);
+    _mav_put_int16_t(buf, 43, volt_2);
     _mav_put_uint8_t_array(buf, 33, reserve, 4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
 #else
@@ -323,6 +367,10 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_chan(uint8_t system_
     packet.fault = fault;
     packet.engine_state = engine_state;
     packet.index = index;
+    packet.inlet_pressure = inlet_pressure;
+    packet.ge_temp = ge_temp;
+    packet.temp_1 = temp_1;
+    packet.volt_2 = volt_2;
     mav_array_memcpy(packet.reserve, reserve, sizeof(uint8_t)*4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
 #endif
@@ -341,7 +389,7 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_chan(uint8_t system_
  */
 static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus)
 {
-    return mavlink_msg_vk_engine_ecu_staus_pack(system_id, component_id, msg, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve);
+    return mavlink_msg_vk_engine_ecu_staus_pack(system_id, component_id, msg, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve, vk_engine_ecu_staus->inlet_pressure, vk_engine_ecu_staus->ge_temp, vk_engine_ecu_staus->temp_1, vk_engine_ecu_staus->volt_2);
 }
 
 /**
@@ -355,7 +403,7 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode(uint8_t system_id,
  */
 static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus)
 {
-    return mavlink_msg_vk_engine_ecu_staus_pack_chan(system_id, component_id, chan, msg, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve);
+    return mavlink_msg_vk_engine_ecu_staus_pack_chan(system_id, component_id, chan, msg, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve, vk_engine_ecu_staus->inlet_pressure, vk_engine_ecu_staus->ge_temp, vk_engine_ecu_staus->temp_1, vk_engine_ecu_staus->volt_2);
 }
 
 /**
@@ -369,7 +417,7 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode_chan(uint8_t syste
  */
 static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus)
 {
-    return mavlink_msg_vk_engine_ecu_staus_pack_status(system_id, component_id, _status, msg,  vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve);
+    return mavlink_msg_vk_engine_ecu_staus_pack_status(system_id, component_id, _status, msg,  vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve, vk_engine_ecu_staus->inlet_pressure, vk_engine_ecu_staus->ge_temp, vk_engine_ecu_staus->temp_1, vk_engine_ecu_staus->volt_2);
 }
 
 /**
@@ -396,10 +444,14 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode_status(uint8_t sys
  * @param engine_state  engine state
  * @param index  engine index
  * @param reserve  engine state
+ * @param inlet_pressure [hPa] inlet air pressure
+ * @param ge_temp [degC] Ge temperature
+ * @param temp_1 [degC] Ge temperature
+ * @param volt_2 [dV] Ge temperature
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_vk_engine_ecu_staus_send(mavlink_channel_t chan, uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve)
+static inline void mavlink_msg_vk_engine_ecu_staus_send(mavlink_channel_t chan, uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve, uint16_t inlet_pressure, int16_t ge_temp, int16_t temp_1, int16_t volt_2)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN];
@@ -420,6 +472,10 @@ static inline void mavlink_msg_vk_engine_ecu_staus_send(mavlink_channel_t chan,
     _mav_put_uint8_t(buf, 30, fault);
     _mav_put_uint8_t(buf, 31, engine_state);
     _mav_put_uint8_t(buf, 32, index);
+    _mav_put_uint16_t(buf, 37, inlet_pressure);
+    _mav_put_int16_t(buf, 39, ge_temp);
+    _mav_put_int16_t(buf, 41, temp_1);
+    _mav_put_int16_t(buf, 43, volt_2);
     _mav_put_uint8_t_array(buf, 33, reserve, 4);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
 #else
@@ -441,6 +497,10 @@ static inline void mavlink_msg_vk_engine_ecu_staus_send(mavlink_channel_t chan,
     packet.fault = fault;
     packet.engine_state = engine_state;
     packet.index = index;
+    packet.inlet_pressure = inlet_pressure;
+    packet.ge_temp = ge_temp;
+    packet.temp_1 = temp_1;
+    packet.volt_2 = volt_2;
     mav_array_memcpy(packet.reserve, reserve, sizeof(uint8_t)*4);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, (const char *)&packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
 #endif
@@ -454,7 +514,7 @@ static inline void mavlink_msg_vk_engine_ecu_staus_send(mavlink_channel_t chan,
 static inline void mavlink_msg_vk_engine_ecu_staus_send_struct(mavlink_channel_t chan, const mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_vk_engine_ecu_staus_send(chan, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve);
+    mavlink_msg_vk_engine_ecu_staus_send(chan, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve, vk_engine_ecu_staus->inlet_pressure, vk_engine_ecu_staus->ge_temp, vk_engine_ecu_staus->temp_1, vk_engine_ecu_staus->volt_2);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, (const char *)vk_engine_ecu_staus, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
 #endif
@@ -468,7 +528,7 @@ static inline void mavlink_msg_vk_engine_ecu_staus_send_struct(mavlink_channel_t
   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_engine_ecu_staus_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve)
+static inline void mavlink_msg_vk_engine_ecu_staus_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve, uint16_t inlet_pressure, int16_t ge_temp, int16_t temp_1, int16_t volt_2)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -489,6 +549,10 @@ static inline void mavlink_msg_vk_engine_ecu_staus_send_buf(mavlink_message_t *m
     _mav_put_uint8_t(buf, 30, fault);
     _mav_put_uint8_t(buf, 31, engine_state);
     _mav_put_uint8_t(buf, 32, index);
+    _mav_put_uint16_t(buf, 37, inlet_pressure);
+    _mav_put_int16_t(buf, 39, ge_temp);
+    _mav_put_int16_t(buf, 41, temp_1);
+    _mav_put_int16_t(buf, 43, volt_2);
     _mav_put_uint8_t_array(buf, 33, reserve, 4);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
 #else
@@ -510,6 +574,10 @@ static inline void mavlink_msg_vk_engine_ecu_staus_send_buf(mavlink_message_t *m
     packet->fault = fault;
     packet->engine_state = engine_state;
     packet->index = index;
+    packet->inlet_pressure = inlet_pressure;
+    packet->ge_temp = ge_temp;
+    packet->temp_1 = temp_1;
+    packet->volt_2 = volt_2;
     mav_array_memcpy(packet->reserve, reserve, sizeof(uint8_t)*4);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, (const char *)packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
 #endif
@@ -703,6 +771,46 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_reserve(const mavlink
     return _MAV_RETURN_uint8_t_array(msg, reserve, 4,  33);
 }
 
+/**
+ * @brief Get field inlet_pressure from vk_engine_ecu_staus message
+ *
+ * @return [hPa] inlet air pressure
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_inlet_pressure(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  37);
+}
+
+/**
+ * @brief Get field ge_temp from vk_engine_ecu_staus message
+ *
+ * @return [degC] Ge temperature
+ */
+static inline int16_t mavlink_msg_vk_engine_ecu_staus_get_ge_temp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  39);
+}
+
+/**
+ * @brief Get field temp_1 from vk_engine_ecu_staus message
+ *
+ * @return [degC] Ge temperature
+ */
+static inline int16_t mavlink_msg_vk_engine_ecu_staus_get_temp_1(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  41);
+}
+
+/**
+ * @brief Get field volt_2 from vk_engine_ecu_staus message
+ *
+ * @return [dV] Ge temperature
+ */
+static inline int16_t mavlink_msg_vk_engine_ecu_staus_get_volt_2(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  43);
+}
+
 /**
  * @brief Decode a vk_engine_ecu_staus message into a struct
  *
@@ -730,6 +838,10 @@ static inline void mavlink_msg_vk_engine_ecu_staus_decode(const mavlink_message_
     vk_engine_ecu_staus->engine_state = mavlink_msg_vk_engine_ecu_staus_get_engine_state(msg);
     vk_engine_ecu_staus->index = mavlink_msg_vk_engine_ecu_staus_get_index(msg);
     mavlink_msg_vk_engine_ecu_staus_get_reserve(msg, vk_engine_ecu_staus->reserve);
+    vk_engine_ecu_staus->inlet_pressure = mavlink_msg_vk_engine_ecu_staus_get_inlet_pressure(msg);
+    vk_engine_ecu_staus->ge_temp = mavlink_msg_vk_engine_ecu_staus_get_ge_temp(msg);
+    vk_engine_ecu_staus->temp_1 = mavlink_msg_vk_engine_ecu_staus_get_temp_1(msg);
+    vk_engine_ecu_staus->volt_2 = mavlink_msg_vk_engine_ecu_staus_get_volt_2(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN? msg->len : MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN;
         memset(vk_engine_ecu_staus, 0, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);

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

@@ -388,7 +388,7 @@ static void mavlink_test_vk_engine_ecu_staus(uint8_t system_id, uint8_t componen
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_vk_engine_ecu_staus_t packet_in = {
-        963497464,963497672,17651,17755,17859,17963,18067,18171,18275,18379,18483,18587,89,156,223,34,101,{ 168, 169, 170, 171 }
+        963497464,963497672,17651,17755,17859,17963,18067,18171,18275,18379,18483,18587,89,156,223,34,101,{ 168, 169, 170, 171 },19159,19263,19367,19471
     };
     mavlink_vk_engine_ecu_staus_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -409,6 +409,10 @@ static void mavlink_test_vk_engine_ecu_staus(uint8_t system_id, uint8_t componen
         packet1.fault = packet_in.fault;
         packet1.engine_state = packet_in.engine_state;
         packet1.index = packet_in.index;
+        packet1.inlet_pressure = packet_in.inlet_pressure;
+        packet1.ge_temp = packet_in.ge_temp;
+        packet1.temp_1 = packet_in.temp_1;
+        packet1.volt_2 = packet_in.volt_2;
         
         mav_array_memcpy(packet1.reserve, packet_in.reserve, sizeof(uint8_t)*4);
         
@@ -424,12 +428,12 @@ static void mavlink_test_vk_engine_ecu_staus(uint8_t system_id, uint8_t componen
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_engine_ecu_staus_pack(system_id, component_id, &msg , packet1.timestamp , packet1.spd_rpm , packet1.thr_pos , packet1.fuel_pos , packet1.cylinderA_temp , packet1.cylinderB_temp , packet1.coolant_temp , packet1.fuel_remain , packet1.alarm , packet1.total_runtime , packet1.runtime , packet1.service_time , packet1.output_volt , packet1.output_curr , packet1.fault , packet1.engine_state , packet1.index , packet1.reserve );
+    mavlink_msg_vk_engine_ecu_staus_pack(system_id, component_id, &msg , packet1.timestamp , packet1.spd_rpm , packet1.thr_pos , packet1.fuel_pos , packet1.cylinderA_temp , packet1.cylinderB_temp , packet1.coolant_temp , packet1.fuel_remain , packet1.alarm , packet1.total_runtime , packet1.runtime , packet1.service_time , packet1.output_volt , packet1.output_curr , packet1.fault , packet1.engine_state , packet1.index , packet1.reserve , packet1.inlet_pressure , packet1.ge_temp , packet1.temp_1 , packet1.volt_2 );
     mavlink_msg_vk_engine_ecu_staus_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_engine_ecu_staus_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.spd_rpm , packet1.thr_pos , packet1.fuel_pos , packet1.cylinderA_temp , packet1.cylinderB_temp , packet1.coolant_temp , packet1.fuel_remain , packet1.alarm , packet1.total_runtime , packet1.runtime , packet1.service_time , packet1.output_volt , packet1.output_curr , packet1.fault , packet1.engine_state , packet1.index , packet1.reserve );
+    mavlink_msg_vk_engine_ecu_staus_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.spd_rpm , packet1.thr_pos , packet1.fuel_pos , packet1.cylinderA_temp , packet1.cylinderB_temp , packet1.coolant_temp , packet1.fuel_remain , packet1.alarm , packet1.total_runtime , packet1.runtime , packet1.service_time , packet1.output_volt , packet1.output_curr , packet1.fault , packet1.engine_state , packet1.index , packet1.reserve , packet1.inlet_pressure , packet1.ge_temp , packet1.temp_1 , packet1.volt_2 );
     mavlink_msg_vk_engine_ecu_staus_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -442,7 +446,7 @@ static void mavlink_test_vk_engine_ecu_staus(uint8_t system_id, uint8_t componen
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_engine_ecu_staus_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.spd_rpm , packet1.thr_pos , packet1.fuel_pos , packet1.cylinderA_temp , packet1.cylinderB_temp , packet1.coolant_temp , packet1.fuel_remain , packet1.alarm , packet1.total_runtime , packet1.runtime , packet1.service_time , packet1.output_volt , packet1.output_curr , packet1.fault , packet1.engine_state , packet1.index , packet1.reserve );
+    mavlink_msg_vk_engine_ecu_staus_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.spd_rpm , packet1.thr_pos , packet1.fuel_pos , packet1.cylinderA_temp , packet1.cylinderB_temp , packet1.coolant_temp , packet1.fuel_remain , packet1.alarm , packet1.total_runtime , packet1.runtime , packet1.service_time , packet1.output_volt , packet1.output_curr , packet1.fault , packet1.engine_state , packet1.index , packet1.reserve , packet1.inlet_pressure , packet1.ge_temp , packet1.temp_1 , packet1.volt_2 );
     mavlink_msg_vk_engine_ecu_staus_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 Mar 31 2026"
+#define MAVLINK_BUILD_DATE "Wed Apr 01 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 7069897735541995260
+#define MAVLINK_COMMON_XML_HASH -3445670045918479351
 
 #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 7069897735541995260
+#define MAVLINK_PRIMARY_XML_HASH -3445670045918479351
 
 #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 Mar 31 2026"
+#define MAVLINK_BUILD_DATE "Wed Apr 01 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 -8425130030743674314
+#define MAVLINK_PRIMARY_XML_HASH -8220065756402345545
 
 #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 -8425130030743674314
+#define MAVLINK_MINIMAL_XML_HASH -8220065756402345545
 
 #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 Mar 31 2026"
+#define MAVLINK_BUILD_DATE "Wed Apr 01 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 -7463754958872367563
+#define MAVLINK_PRIMARY_XML_HASH 7318385347264150845
 
 #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 -7463754958872367563
+#define MAVLINK_STANDARD_XML_HASH 7318385347264150845
 
 #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 Mar 31 2026"
+#define MAVLINK_BUILD_DATE "Wed Apr 01 2026"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
  

Některé soubory nejsou zobrazeny, neboť je v těchto rozdílových datech změněno mnoho souborů