Browse Source

增加教培航点相关指令

Liu Yang 3 weeks ago
parent
commit
58c2145407

+ 24 - 0
msg_definitions/VKFly.xml

@@ -664,6 +664,18 @@
         <param index="7" label="Altitude" units="m">Altitude</param>
       </entry>
 
+      <entry value="44013" name="VKFLY_CMD_NAV_EDU_TRAINING" hasLocation="true"
+        isDestination="true">
+        <description>VLFLY Custom orbit waypoint </description>
+        <param index="1" label="Hold Time And Speed"> </param>
+        <param index="2" label="Alt Mode And Speed"> </param>
+        <param index="3" label="Param3"> </param>
+        <param index="4" label="Yaw Mode"> </param>
+        <param index="5" label="Latitude">Latitude</param>
+        <param index="6" label="Longitude">Longitude</param>
+        <param index="7" label="Altitude" units="m">Altitude</param>
+      </entry>
+
       <entry value="44030" name="VKFLY_CMD_MOUNT_CTRL" hasLocation="true"
         isDestination="true">
         <description>VLFLY Custom orbit waypoint </description>
@@ -791,6 +803,18 @@
         <param index="7" label="Alt"> </param>
       </entry>
 
+      <entry value="44067" name="VKFLY_CMD_MISSION_START_EDU_TRAINING" hasLocation="false"
+        isDestination="false">
+        <description>Start mission</description>
+        <param index="1" label="Start Seq" minValue="0" maxValue="65535">start sequence of mission</param>
+        <param index="2" label="Loop Count"> </param>
+        <param index="3" label="Mission Done Action" enum="VKFLY_MISSION_DONE_ACT"> </param>
+        <param index="4" label=""> </param>
+        <param index="5" label=""> </param>
+        <param index="6" label=""> </param>
+        <param index="7" label=""> </param>
+      </entry>
+
     </enum>
   </enums>
 

+ 42 - 0
readme.md

@@ -1037,6 +1037,39 @@ param3 分为 byte[4] 进行使用.
 | param6 | 经度 1e-7deg                                                                                                                                                                                                                                                                                                        |
 | param7 | 高度 m                                                                                                                                                                                                                                                                                                              |
 
+### 5.1.6 教培航点 VKFLY_CMD_NAV_EDU_TRAINING
+
+使用 MISSION_ITEM_INT 消息定义传输教培航点
+
+* param1
+  该参数按 byte[4] 进行使用
+  | 字节        | 类型  | 说明                                                 |
+  | ----------- | ----- | ---------------------------------------------------- |
+  | byte0-byte1 | int16 | 悬停时间, 单位 s. 0表示不进行悬停自动协调转弯        |
+  | byte2-byte3 | int16 | 巡航速度, 单位 dm/s. 0或负数表示使用默认巡航速度参数 |
+* param2
+  该参数按 byte[4] 进行使用
+  | 字节        | 类型  | 说明                                                 |
+  | ----------- | ----- | ---------------------------------------------------- |
+  | byte0       | uint8 | 高度执行方式, 0-坡度执行, 1-先到高度再水平执行       |
+  | byte1       | uint8 | 预留                                                 |
+  | byte2-byte3 | int16 | 垂直速度, 单位 dm/s. 0或负数表示使用默认巡航速度参数 |
+* param3
+  预留
+* param4
+  该参数作为 byte[4] 类型使用
+  | 字节        | 类型  | 说明                                                                                                                                                                |
+  | ----------- | ----- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
+  | byte0       | uint8 | 航向模式, 参考 VKFLY_YAW_CTRL_MODE                                                                                                                                  |
+  | byte1       | uint8 | 预留                                                                                                                                                                |
+  | byte2-byte3 | int16 | 航向值, 范围-180-180, 当航向模式为 VKFLY_YAW_TO_SETVAL 时表示给定的航向值, 单位deg. 当航向模式为指向 <br>HOME 或 NEXT_WP 或 INTEREST 等给定点时, 表示叠加的航向偏移 |
+* xy
+  经纬度, 单位 1e-7deg
+* z
+  高度, 单位 m. 通过 frame 来判断高度是否为相对高度还是绝对高度
+  MAV_FRAME_GLOBAL_RELATIVE_ALT: 相对高度
+  MAV_FRAME_GLOBAL_ALT: 海拔高度
+
 ### 4.2 电子围栏 MAV_MISSION_TYPE_FENCE (未实施)
 
 飞控一共有200个电子围栏点.
@@ -1456,6 +1489,15 @@ param1~param5中,
 | param1 | 目标模态, MAV_VTOL_STATE_MC 旋翼, MAV_VTOL_STATE_FW 固定翼 |
 | param2 | 是否立刻切换, 填0                                          |
 
+### 5.41 教培开始航线 VKFLY_CMD_MISSION_START_EDU_TRAINING
+* param1
+  起始航点序号, 0-UINT16_MAX
+* param2
+  执行循环次数, -1表示无限循环, 其它取 1~UINT16_MAX
+* param3
+  航线完成后动作, 参考 VKFLY_MISSION_DONE_ACT
+
+
 ## 6 飞控 LOG 读取
 
 - LOG_REQUEST_LIST

+ 4 - 2
v2.0/VKFly/VKFly.h

@@ -10,7 +10,7 @@
     #error Wrong include order: MAVLINK_VKFLY.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_VKFLY_XML_HASH -5223598330246455531
+#define MAVLINK_VKFLY_XML_HASH 1592171951267676919
 
 #ifdef __cplusplus
 extern "C" {
@@ -487,6 +487,7 @@ typedef enum VKFLY_CMD
    VKFLY_CMD_NAV_WP=44010, /* VKFLY custom takephoto waypoint commond. | |  |  | Yaw control mode| Latitude| Longitude| Altitude|  */
    VKFLY_CMD_NAV_WP_THROW=44011, /* VKFLY custom throwing waypoint command.  | | | Reserved.| Yaw control mode.| Latitude| Longitude| Altitude|  */
    VKFLY_CMD_NAV_WP_ORBIT_DO_PHOTO=44012, /* VLFLY Custom orbit waypoint  | |  |  |  | Latitude| Longitude| Altitude|  */
+   VKFLY_CMD_NAV_EDU_TRAINING=44013, /* VLFLY Custom orbit waypoint  | |  |  |  | Latitude| Longitude| Altitude|  */
    VKFLY_CMD_MOUNT_CTRL=44030, /* VLFLY Custom orbit waypoint  | |  |  |  | Latitude| Longitude| Altitude|  */
    VKFLY_CMD_FORMATION_FLY=44031, /* Formation fly assemble, disband or change formation |1 means assemble, 2 means quit, 3 means change formation| | | | | | |  */
    VKFLY_CMD_ESC_CONFIG=44050, /* can esc id configuration | Set Esc id, min=1, max=16 |  |  |  |  |  |  |  */
@@ -505,7 +506,8 @@ typedef enum VKFLY_CMD
           in clockwise.|  NAN means ignore. 1 means do goto rtl circle point right
           now.
         |  |  |  |  |  |  */
-   VKFLY_CMD_ENUM_END=44067, /*  | */
+   VKFLY_CMD_MISSION_START_EDU_TRAINING=44067, /* Start mission |start sequence of mission|  |  |  |  |  |  |  */
+   VKFLY_CMD_ENUM_END=44068, /*  | */
 } VKFLY_CMD;
 #endif
 

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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -5223598330246455531
+#define MAVLINK_PRIMARY_XML_HASH 1592171951267676919
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Sat Jul 05 2025"
+#define MAVLINK_BUILD_DATE "Mon Jul 07 2025"
 #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 1708057333764453208
+#define MAVLINK_COMMON_XML_HASH 1368628791415804270
 
 #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 1708057333764453208
+#define MAVLINK_PRIMARY_XML_HASH 1368628791415804270
 
 #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 "Sat Jul 05 2025"
+#define MAVLINK_BUILD_DATE "Mon Jul 07 2025"
 #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 -7453342355037382492
+#define MAVLINK_PRIMARY_XML_HASH -5627380079814967233
 
 #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 -7453342355037382492
+#define MAVLINK_MINIMAL_XML_HASH -5627380079814967233
 
 #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 "Sat Jul 05 2025"
+#define MAVLINK_BUILD_DATE "Mon Jul 07 2025"
 #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 -3068734849600737466
+#define MAVLINK_PRIMARY_XML_HASH 3342795328012072205
 
 #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 -3068734849600737466
+#define MAVLINK_STANDARD_XML_HASH 3342795328012072205
 
 #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 "Sat Jul 05 2025"
+#define MAVLINK_BUILD_DATE "Mon Jul 07 2025"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22