From cf42ba1501f54f5fb4900dcb23d86d6da6cc5fa7 Mon Sep 17 00:00:00 2001 From: tk Date: Fri, 26 Jul 2024 19:06:57 +0800 Subject: [PATCH] =?UTF-8?q?=E3=80=90=E7=B1=BB=20=20=E5=9E=8B=E3=80=91?= =?UTF-8?q?=EF=BC=9Afix=20=E4=BF=AE=E6=94=B9=E4=B9=8B=E5=89=8D=E5=90=91?= =?UTF-8?q?=E9=A3=9E=E6=8E=A7=E8=AF=B7=E6=B1=82=E6=95=B0=E6=8D=AE=E6=B5=81?= =?UTF-8?q?=E7=9A=84=E6=96=B9=E5=BC=8F=20=E3=80=90=E5=8E=9F=20=20=E5=9B=A0?= =?UTF-8?q?=E3=80=91=EF=BC=9A=EF=BC=88=E5=A5=BD=E5=A4=84=EF=BC=8C=E4=B8=8D?= =?UTF-8?q?=E4=BC=9A=E6=9C=89=E9=A3=9E=E6=8E=A7=E6=BB=9E=E5=90=8E=E5=90=AF?= =?UTF-8?q?=E5=8A=A8=E9=97=AE=E9=A2=98=20=E4=B8=8D=E7=94=A8=E4=B8=80?= =?UTF-8?q?=E7=9B=B4=E5=8F=91=E9=80=81=E8=AF=B7=E6=B1=82=EF=BC=89=20?= =?UTF-8?q?=E3=80=90=E8=BF=87=20=20=E7=A8=8B=E3=80=91=EF=BC=9A=E8=80=81?= =?UTF-8?q?=E7=9A=84=E6=96=B9=E5=BC=8F=EF=BC=9A=E6=A3=80=E6=B5=8B=E7=AC=AC?= =?UTF-8?q?=E4=B8=80=E4=B8=AA=E5=BF=83=E8=B7=B3=E6=98=AF=20=E6=A3=80?= =?UTF-8?q?=E6=B5=8B=E8=AF=B7=E6=B1=82=E4=B8=8E=E5=90=A6=20=E6=B2=A1?= =?UTF-8?q?=E6=9C=89=E5=B0=B1=E8=AF=B7=E6=B1=82=E6=95=B0=E6=8D=AE=EF=BC=8C?= =?UTF-8?q?=E5=8F=A6=E5=A4=96=E6=AF=8F50=E7=A7=92=E5=BC=BA=E5=88=B6?= =?UTF-8?q?=E8=AF=B7=E6=B1=82=E4=B8=80=E6=AC=A1=E3=80=82=E6=96=B0=E7=9A=84?= =?UTF-8?q?=E6=96=B9=E5=BC=8F=EF=BC=9A=E6=A3=80=E6=B5=8B=E7=94=B5=E6=B5=81?= =?UTF-8?q?=E5=AD=97=E6=AE=B5=E6=98=AF=E5=90=A6=E8=B5=8B=E8=BF=87=E5=80=BC?= =?UTF-8?q?=20=E6=B2=A1=E6=9C=89=E8=B5=8B=E5=80=BC=E5=B0=B1=E4=B8=80?= =?UTF-8?q?=E7=9B=B4=E8=AF=B7=E6=B1=82=20=E7=9B=B4=E5=88=B0=E6=94=B6?= =?UTF-8?q?=E5=88=B0=E9=A3=9E=E6=8E=A7=E7=9A=84=E6=95=B0=E6=8D=AE=E6=B5=81?= =?UTF-8?q?=E3=80=82=20=E3=80=90=E5=BD=B1=20=20=E5=93=8D=E3=80=91=EF=BC=9A?= =?UTF-8?q?=E5=88=A0=E6=8E=89=E4=B9=8B=E5=89=8D=E7=9B=B8=E5=85=B3=E7=9A=84?= =?UTF-8?q?=E6=A3=80=E6=B5=8B=E7=AC=AC=E4=B8=80=E6=AC=A1=E5=8F=91=E9=80=81?= =?UTF-8?q?=E7=8A=B6=E6=80=81=E7=9A=84=E7=9B=B8=E5=85=B3=E4=BB=A3=E7=A0=81?= =?UTF-8?q?=EF=BC=8C=E5=88=A0=E6=8E=89=E4=BA=86=E6=AF=8F50=E7=A7=92?= =?UTF-8?q?=E8=AF=B7=E6=B1=82=E7=9A=84=E7=9B=B8=E5=85=B3=E4=BB=A3=E7=A0=81?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # 类型 包含: # feat:新功能(feature) # fix:修补bug # docs:文档(documentation) # style: 格式(不影响代码运行的变动) # refactor:重构(即不是新增功能,也不是修改bug的代码变动) # test:增加测试 # chore:构建过程或辅助工具的变动 --- lib/mavlink/common/common.h | 573 ++++++++++++++++++------------------ src/FoodDeliveryBase.cpp | 22 +- src/FoodDeliveryBase.h | 7 +- src/commser.cpp | 62 ++-- src/commser.h | 1 - src/main.cpp | 5 +- 6 files changed, 349 insertions(+), 321 deletions(-) diff --git a/lib/mavlink/common/common.h b/lib/mavlink/common/common.h index 2a92cc8..ee92222 100644 --- a/lib/mavlink/common/common.h +++ b/lib/mavlink/common/common.h @@ -6,10 +6,11 @@ #define COMMON_H #ifdef __cplusplus -extern "C" { +extern "C" +{ #endif -// MESSAGE LENGTHS AND CRCS + // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS #define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 54, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} @@ -20,16 +21,25 @@ extern "C" { #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"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_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"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_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO \ + { \ + MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"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_SET_MODE, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"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_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"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_VFR_HUD, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"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_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"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_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"EMPTY", 0, {{"", "", MAVLINK_TYPE_CHAR, 0, 0, 0}}}, {"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_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, \ + { \ + "EMPTY", 0, \ + { \ + { \ + "", "", MAVLINK_TYPE_CHAR, 0, 0, 0 \ + } \ + } \ + } \ + } #endif #include "../protocol.h" #define MAVLINK_ENABLED_COMMON - - -// MAVLINK VERSION + // MAVLINK VERSION #ifndef MAVLINK_VERSION #define MAVLINK_VERSION 3 @@ -42,372 +52,373 @@ extern "C" { // ENUM DEFINITIONS - /** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */ #ifndef HAVE_ENUM_MAV_AUTOPILOT #define HAVE_ENUM_MAV_AUTOPILOT -enum MAV_AUTOPILOT -{ - MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */ - MAV_AUTOPILOT_PIXHAWK=1, /* PIXHAWK autopilot, http://pixhawk.ethz.ch | */ - MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */ - MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */ - MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */ - MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */ - MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */ - MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */ - MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */ - MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */ - MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */ - MAV_AUTOPILOT_FP=11, /* FlexiPilot | */ - MAV_AUTOPILOT_ENUM_END=12, /* | */ -}; + enum MAV_AUTOPILOT + { + MAV_AUTOPILOT_GENERIC = 0, /* Generic autopilot, full support for everything | */ + MAV_AUTOPILOT_PIXHAWK = 1, /* PIXHAWK autopilot, http://pixhawk.ethz.ch | */ + MAV_AUTOPILOT_SLUGS = 2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */ + MAV_AUTOPILOT_ARDUPILOTMEGA = 3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */ + MAV_AUTOPILOT_OPENPILOT = 4, /* OpenPilot, http://openpilot.org | */ + MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5, /* Generic autopilot only supporting simple waypoints | */ + MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6, /* Generic autopilot supporting waypoints and other simple navigation commands | */ + MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7, /* Generic autopilot supporting the full mission command set | */ + MAV_AUTOPILOT_INVALID = 8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */ + MAV_AUTOPILOT_PPZ = 9, /* PPZ UAV - http://nongnu.org/paparazzi | */ + MAV_AUTOPILOT_UDB = 10, /* UAV Dev Board | */ + MAV_AUTOPILOT_FP = 11, /* FlexiPilot | */ + MAV_AUTOPILOT_ENUM_END = 12, /* | */ + }; #endif /** @brief */ #ifndef HAVE_ENUM_MAV_TYPE #define HAVE_ENUM_MAV_TYPE -enum MAV_TYPE -{ - MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */ - MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */ - MAV_TYPE_QUADROTOR=2, /* Quadrotor | */ - MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */ - MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */ - MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */ - MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */ - MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */ - MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */ - MAV_TYPE_ROCKET=9, /* Rocket | */ - MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */ - MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */ - MAV_TYPE_SUBMARINE=12, /* Submarine | */ - MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */ - MAV_TYPE_OCTOROTOR=14, /* Octorotor | */ - MAV_TYPE_TRICOPTER=15, /* Octorotor | */ - MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */ - MAV_TYPE_ENUM_END=17, /* | */ -}; + enum MAV_TYPE + { + MAV_TYPE_GENERIC = 0, /* Generic micro air vehicle. | */ + MAV_TYPE_FIXED_WING = 1, /* Fixed wing aircraft. | */ + MAV_TYPE_QUADROTOR = 2, /* Quadrotor | */ + MAV_TYPE_COAXIAL = 3, /* Coaxial helicopter | */ + MAV_TYPE_HELICOPTER = 4, /* Normal helicopter with tail rotor. | */ + MAV_TYPE_ANTENNA_TRACKER = 5, /* Ground installation | */ + MAV_TYPE_GCS = 6, /* Operator control unit / ground control station | */ + MAV_TYPE_AIRSHIP = 7, /* Airship, controlled | */ + MAV_TYPE_FREE_BALLOON = 8, /* Free balloon, uncontrolled | */ + MAV_TYPE_ROCKET = 9, /* Rocket | */ + MAV_TYPE_GROUND_ROVER = 10, /* Ground rover | */ + MAV_TYPE_SURFACE_BOAT = 11, /* Surface vessel, boat, ship | */ + MAV_TYPE_SUBMARINE = 12, /* Submarine | */ + MAV_TYPE_HEXAROTOR = 13, /* Hexarotor | */ + MAV_TYPE_OCTOROTOR = 14, /* Octorotor | */ + MAV_TYPE_TRICOPTER = 15, /* Octorotor | */ + MAV_TYPE_FLAPPING_WING = 16, /* Flapping wing | */ + MAV_TYPE_ENUM_END = 17, /* | */ + }; #endif /** @brief These flags encode the MAV mode. */ #ifndef HAVE_ENUM_MAV_MODE_FLAG #define HAVE_ENUM_MAV_MODE_FLAG -enum MAV_MODE_FLAG -{ - MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */ - MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */ - MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */ - MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */ - MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */ - MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */ - MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */ - MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */ - MAV_MODE_FLAG_ENUM_END=129, /* | */ -}; + enum MAV_MODE_FLAG + { + MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1, /* 0b00000001 Reserved for future use. | */ + MAV_MODE_FLAG_TEST_ENABLED = 2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */ + MAV_MODE_FLAG_AUTO_ENABLED = 4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */ + MAV_MODE_FLAG_GUIDED_ENABLED = 8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */ + MAV_MODE_FLAG_STABILIZE_ENABLED = 16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */ + MAV_MODE_FLAG_HIL_ENABLED = 32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */ + MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64, /* 0b01000000 remote control input is enabled. | */ + MAV_MODE_FLAG_SAFETY_ARMED = 128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */ + MAV_MODE_FLAG_ENUM_END = 129, /* | */ + }; #endif /** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */ #ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION #define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION -enum MAV_MODE_FLAG_DECODE_POSITION -{ - MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */ - MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */ - MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit: 00000100 | */ - MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */ - MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */ - MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */ - MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */ - MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */ - MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */ -}; + enum MAV_MODE_FLAG_DECODE_POSITION + { + MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1, /* Eighth bit: 00000001 | */ + MAV_MODE_FLAG_DECODE_POSITION_TEST = 2, /* Seventh bit: 00000010 | */ + MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4, /* Sixt bit: 00000100 | */ + MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8, /* Fifth bit: 00001000 | */ + MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16, /* Fourth bit: 00010000 | */ + MAV_MODE_FLAG_DECODE_POSITION_HIL = 32, /* Third bit: 00100000 | */ + MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64, /* Second bit: 01000000 | */ + MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128, /* First bit: 10000000 | */ + MAV_MODE_FLAG_DECODE_POSITION_ENUM_END = 129, /* | */ + }; #endif /** @brief Override command, pauses current mission execution and moves immediately to a position */ #ifndef HAVE_ENUM_MAV_GOTO #define HAVE_ENUM_MAV_GOTO -enum MAV_GOTO -{ - MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */ - MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */ - MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */ - MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */ - MAV_GOTO_ENUM_END=4, /* | */ -}; + enum MAV_GOTO + { + MAV_GOTO_DO_HOLD = 0, /* Hold at the current position. | */ + MAV_GOTO_DO_CONTINUE = 1, /* Continue with the next item in mission execution. | */ + MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2, /* Hold at the current position of the system | */ + MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3, /* Hold at the position specified in the parameters of the DO_HOLD action | */ + MAV_GOTO_ENUM_END = 4, /* | */ + }; #endif /** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it - simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */ + simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */ #ifndef HAVE_ENUM_MAV_MODE #define HAVE_ENUM_MAV_MODE -enum MAV_MODE -{ - MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */ - MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */ - MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ - MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */ - MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */ - MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ - MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */ - MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ - MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */ - MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */ - MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ - MAV_MODE_ENUM_END=221, /* | */ -}; + enum MAV_MODE + { + MAV_MODE_PREFLIGHT = 0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */ + MAV_MODE_MANUAL_DISARMED = 64, /* System is allowed to be active, under manual (RC) control, no stabilization | */ + MAV_MODE_TEST_DISARMED = 66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ + MAV_MODE_STABILIZE_DISARMED = 80, /* System is allowed to be active, under assisted RC control. | */ + MAV_MODE_GUIDED_DISARMED = 88, /* System is allowed to be active, under autonomous control, manual setpoint | */ + MAV_MODE_AUTO_DISARMED = 92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ + MAV_MODE_MANUAL_ARMED = 192, /* System is allowed to be active, under manual (RC) control, no stabilization | */ + MAV_MODE_TEST_ARMED = 194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ + MAV_MODE_STABILIZE_ARMED = 208, /* System is allowed to be active, under assisted RC control. | */ + MAV_MODE_GUIDED_ARMED = 216, /* System is allowed to be active, under autonomous control, manual setpoint | */ + MAV_MODE_AUTO_ARMED = 220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ + MAV_MODE_ENUM_END = 221, /* | */ + }; #endif /** @brief */ #ifndef HAVE_ENUM_MAV_STATE #define HAVE_ENUM_MAV_STATE -enum MAV_STATE -{ - MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */ - MAV_STATE_BOOT=1, /* System is booting up. | */ - MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */ - MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */ - MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */ - MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */ - MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */ - MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */ - MAV_STATE_ENUM_END=8, /* | */ -}; + enum MAV_STATE + { + MAV_STATE_UNINIT = 0, /* Uninitialized system, state is unknown. | */ + MAV_STATE_BOOT = 1, /* System is booting up. | */ + MAV_STATE_CALIBRATING = 2, /* System is calibrating and not flight-ready. | */ + MAV_STATE_STANDBY = 3, /* System is grounded and on standby. It can be launched any time. | */ + MAV_STATE_ACTIVE = 4, /* System is active and might be already airborne. Motors are engaged. | */ + MAV_STATE_CRITICAL = 5, /* System is in a non-normal flight mode. It can however still navigate. | */ + MAV_STATE_EMERGENCY = 6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */ + MAV_STATE_POWEROFF = 7, /* System just initialized its power-down sequence, will shut down now. | */ + MAV_STATE_ENUM_END = 8, /* | */ + }; #endif /** @brief */ #ifndef HAVE_ENUM_MAV_COMPONENT #define HAVE_ENUM_MAV_COMPONENT -enum MAV_COMPONENT -{ - MAV_COMP_ID_ALL=0, /* | */ - MAV_COMP_ID_CAMERA=100, /* | */ - MAV_COMP_ID_SERVO1=140, /* | */ - MAV_COMP_ID_SERVO2=141, /* | */ - MAV_COMP_ID_SERVO3=142, /* | */ - MAV_COMP_ID_SERVO4=143, /* | */ - MAV_COMP_ID_SERVO5=144, /* | */ - MAV_COMP_ID_SERVO6=145, /* | */ - MAV_COMP_ID_SERVO7=146, /* | */ - MAV_COMP_ID_SERVO8=147, /* | */ - MAV_COMP_ID_SERVO9=148, /* | */ - MAV_COMP_ID_SERVO10=149, /* | */ - MAV_COMP_ID_SERVO11=150, /* | */ - MAV_COMP_ID_SERVO12=151, /* | */ - MAV_COMP_ID_SERVO13=152, /* | */ - MAV_COMP_ID_SERVO14=153, /* | */ - MAV_COMP_ID_MAPPER=180, /* | */ - MAV_COMP_ID_MISSIONPLANNER=190, /* | */ - MAV_COMP_ID_PATHPLANNER=195, /* | */ - MAV_COMP_ID_IMU=200, /* | */ - MAV_COMP_ID_IMU_2=201, /* | */ - MAV_COMP_ID_IMU_3=202, /* | */ - MAV_COMP_ID_GPS=220, /* | */ - MAV_COMP_ID_UDP_BRIDGE=240, /* | */ - MAV_COMP_ID_UART_BRIDGE=241, /* | */ - MAV_COMP_ID_SYSTEM_CONTROL=250, /* | */ - MAV_COMPONENT_ENUM_END=251, /* | */ -}; + enum MAV_COMPONENT + { + MAV_COMP_ID_ALL = 0, /* | */ + MAV_COMP_ID_CAMERA = 100, /* | */ + MAV_COMP_ID_SERVO1 = 140, /* | */ + MAV_COMP_ID_SERVO2 = 141, /* | */ + MAV_COMP_ID_SERVO3 = 142, /* | */ + MAV_COMP_ID_SERVO4 = 143, /* | */ + MAV_COMP_ID_SERVO5 = 144, /* | */ + MAV_COMP_ID_SERVO6 = 145, /* | */ + MAV_COMP_ID_SERVO7 = 146, /* | */ + MAV_COMP_ID_SERVO8 = 147, /* | */ + MAV_COMP_ID_SERVO9 = 148, /* | */ + MAV_COMP_ID_SERVO10 = 149, /* | */ + MAV_COMP_ID_SERVO11 = 150, /* | */ + MAV_COMP_ID_SERVO12 = 151, /* | */ + MAV_COMP_ID_SERVO13 = 152, /* | */ + MAV_COMP_ID_SERVO14 = 153, /* | */ + MAV_COMP_ID_MAPPER = 180, /* | */ + MAV_COMP_ID_MISSIONPLANNER = 190, /* | */ + MAV_COMP_ID_PATHPLANNER = 195, /* | */ + MAV_COMP_ID_IMU = 200, /* | */ + MAV_COMP_ID_IMU_2 = 201, /* | */ + MAV_COMP_ID_IMU_3 = 202, /* | */ + MAV_COMP_ID_GPS = 220, /* | */ + MAV_COMP_ID_UDP_BRIDGE = 240, /* | */ + MAV_COMP_ID_UART_BRIDGE = 241, /* | */ + MAV_COMP_ID_SYSTEM_CONTROL = 250, /* | */ + MAV_COMPONENT_ENUM_END = 251, /* | */ + }; #endif /** @brief */ #ifndef HAVE_ENUM_MAV_FRAME #define HAVE_ENUM_MAV_FRAME -enum MAV_FRAME -{ - MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */ - MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */ - MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */ - MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */ - MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */ - MAV_FRAME_ENUM_END=5, /* | */ -}; + enum MAV_FRAME + { + MAV_FRAME_GLOBAL = 0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */ + MAV_FRAME_LOCAL_NED = 1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */ + MAV_FRAME_MISSION = 2, /* NOT a coordinate frame, indicates a mission command. | */ + MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */ + MAV_FRAME_LOCAL_ENU = 4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */ + MAV_FRAME_ENUM_END = 5, /* | */ + }; #endif /** @brief */ #ifndef HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE #define HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE -enum MAVLINK_DATA_STREAM_TYPE -{ - MAVLINK_DATA_STREAM_IMG_JPEG=1, /* | */ - MAVLINK_DATA_STREAM_IMG_BMP=2, /* | */ - MAVLINK_DATA_STREAM_IMG_RAW8U=3, /* | */ - MAVLINK_DATA_STREAM_IMG_RAW32U=4, /* | */ - MAVLINK_DATA_STREAM_IMG_PGM=5, /* | */ - MAVLINK_DATA_STREAM_IMG_PNG=6, /* | */ - MAVLINK_DATA_STREAM_TYPE_ENUM_END=7, /* | */ -}; + enum MAVLINK_DATA_STREAM_TYPE + { + MAVLINK_DATA_STREAM_IMG_JPEG = 1, /* | */ + MAVLINK_DATA_STREAM_IMG_BMP = 2, /* | */ + MAVLINK_DATA_STREAM_IMG_RAW8U = 3, /* | */ + MAVLINK_DATA_STREAM_IMG_RAW32U = 4, /* | */ + MAVLINK_DATA_STREAM_IMG_PGM = 5, /* | */ + MAVLINK_DATA_STREAM_IMG_PNG = 6, /* | */ + MAVLINK_DATA_STREAM_TYPE_ENUM_END = 7, /* | */ + }; #endif /** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ #ifndef HAVE_ENUM_MAV_CMD #define HAVE_ENUM_MAV_CMD -enum MAV_CMD -{ - MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ - MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ - MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - MAV_CMD_ENUM_END=401, /* | */ - MAV_CMD_DO_START_MAG_CAL = 42424,/*磁罗盘校准*/ -}; + enum MAV_CMD + { + MAV_CMD_NAV_WAYPOINT = 16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_UNLIM = 17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TURNS = 18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TIME = 19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_RETURN_TO_LAUNCH = 20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAND = 21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_TAKEOFF = 22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_ROI = 80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_NAV_PATHPLANNING = 81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_LAST = 95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_DELAY = 112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_CHANGE_ALT = 113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ + MAV_CMD_CONDITION_DISTANCE = 114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_YAW = 115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_LAST = 159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE = 176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_JUMP = 177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CHANGE_SPEED = 178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_HOME = 179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_SET_PARAMETER = 180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_RELAY = 181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_RELAY = 182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_SERVO = 183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_SERVO = 184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_CONTROL_VIDEO = 200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ + MAV_CMD_DO_LAST = 240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_CALIBRATION = 241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ + MAV_CMD_PREFLIGHT_STORAGE = 245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ + MAV_CMD_OVERRIDE_GOTO = 252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ + MAV_CMD_MISSION_START = 300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ + MAV_CMD_COMPONENT_ARM_DISARM = 400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ + MAV_CMD_ENUM_END = 401, /* | */ + MAV_CMD_DO_START_MAG_CAL = 42424, /*磁罗盘校准*/ + MAV_CMD_GET_HOME_POSITION = 410, // 请求返航点 410 + }; #endif /** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a - recommendation to the autopilot software. Individual autopilots may or may not obey - the recommended messages. */ + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. */ #ifndef HAVE_ENUM_MAV_DATA_STREAM #define HAVE_ENUM_MAV_DATA_STREAM -enum MAV_DATA_STREAM -{ - MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ - MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ - MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */ - MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */ - MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */ - MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */ - MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_ENUM_END=13, /* | */ -}; + enum MAV_DATA_STREAM + { + MAV_DATA_STREAM_ALL = 0, /* Enable all data streams | */ + MAV_DATA_STREAM_RAW_SENSORS = 1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ + MAV_DATA_STREAM_EXTENDED_STATUS = 2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */ + MAV_DATA_STREAM_RC_CHANNELS = 3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */ + MAV_DATA_STREAM_RAW_CONTROLLER = 4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */ + MAV_DATA_STREAM_POSITION = 6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */ + MAV_DATA_STREAM_EXTRA1 = 10, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_EXTRA2 = 11, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_EXTRA3 = 12, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_ENUM_END = 13, /* | */ + }; #endif /** @brief The ROI (region of interest) for the vehicle. This can be - be used by the vehicle for camera/vehicle attitude alignment (see - MAV_CMD_NAV_ROI). */ + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). */ #ifndef HAVE_ENUM_MAV_ROI #define HAVE_ENUM_MAV_ROI -enum MAV_ROI -{ - MAV_ROI_NONE=0, /* No region of interest. | */ - MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */ - MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */ - MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ - MAV_ROI_TARGET=4, /* Point toward of given id. | */ - MAV_ROI_ENUM_END=5, /* | */ -}; + enum MAV_ROI + { + MAV_ROI_NONE = 0, /* No region of interest. | */ + MAV_ROI_WPNEXT = 1, /* Point toward next MISSION. | */ + MAV_ROI_WPINDEX = 2, /* Point toward given MISSION. | */ + MAV_ROI_LOCATION = 3, /* Point toward fixed location. | */ + MAV_ROI_TARGET = 4, /* Point toward of given id. | */ + MAV_ROI_ENUM_END = 5, /* | */ + }; #endif /** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */ #ifndef HAVE_ENUM_MAV_CMD_ACK #define HAVE_ENUM_MAV_CMD_ACK -enum MAV_CMD_ACK -{ - MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */ - MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */ - MAV_CMD_ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */ - MAV_CMD_ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */ - MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */ - MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */ - MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */ - MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */ - MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */ - MAV_CMD_ACK_ENUM_END=10, /* | */ -}; + enum MAV_CMD_ACK + { + MAV_CMD_ACK_OK = 1, /* Command / mission item is ok. | */ + MAV_CMD_ACK_ERR_FAIL = 2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */ + MAV_CMD_ACK_ERR_ACCESS_DENIED = 3, /* The system is refusing to accept this command from this source / communication partner. | */ + MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4, /* Command or mission item is not supported, other commands would be accepted. | */ + MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5, /* The coordinate frame of this command / mission item is not supported. | */ + MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */ + MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7, /* The X or latitude value is out of range. | */ + MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8, /* The Y or longitude value is out of range. | */ + MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9, /* The Z or altitude value is out of range. | */ + MAV_CMD_ACK_ENUM_END = 10, /* | */ + }; #endif /** @brief type of a mavlink parameter */ #ifndef HAVE_ENUM_MAV_VAR #define HAVE_ENUM_MAV_VAR -enum MAV_VAR -{ - MAV_VAR_FLOAT=0, /* 32 bit float | */ - MAV_VAR_UINT8=1, /* 8 bit unsigned integer | */ - MAV_VAR_INT8=2, /* 8 bit signed integer | */ - MAV_VAR_UINT16=3, /* 16 bit unsigned integer | */ - MAV_VAR_INT16=4, /* 16 bit signed integer | */ - MAV_VAR_UINT32=5, /* 32 bit unsigned integer | */ - MAV_VAR_INT32=6, /* 32 bit signed integer | */ - MAV_VAR_ENUM_END=7, /* | */ -}; + enum MAV_VAR + { + MAV_VAR_FLOAT = 0, /* 32 bit float | */ + MAV_VAR_UINT8 = 1, /* 8 bit unsigned integer | */ + MAV_VAR_INT8 = 2, /* 8 bit signed integer | */ + MAV_VAR_UINT16 = 3, /* 16 bit unsigned integer | */ + MAV_VAR_INT16 = 4, /* 16 bit signed integer | */ + MAV_VAR_UINT32 = 5, /* 32 bit unsigned integer | */ + MAV_VAR_INT32 = 6, /* 32 bit signed integer | */ + MAV_VAR_ENUM_END = 7, /* | */ + }; #endif /** @brief result from a mavlink command */ #ifndef HAVE_ENUM_MAV_RESULT #define HAVE_ENUM_MAV_RESULT -enum MAV_RESULT -{ - MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */ - MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */ - MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */ - MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */ - MAV_RESULT_FAILED=4, /* Command executed, but failed | */ - MAV_RESULT_ENUM_END=5, /* | */ -}; + enum MAV_RESULT + { + MAV_RESULT_ACCEPTED = 0, /* Command ACCEPTED and EXECUTED | */ + MAV_RESULT_TEMPORARILY_REJECTED = 1, /* Command TEMPORARY REJECTED/DENIED | */ + MAV_RESULT_DENIED = 2, /* Command PERMANENTLY DENIED | */ + MAV_RESULT_UNSUPPORTED = 3, /* Command UNKNOWN/UNSUPPORTED | */ + MAV_RESULT_FAILED = 4, /* Command executed, but failed | */ + MAV_RESULT_ENUM_END = 5, /* | */ + }; #endif /** @brief result in a mavlink mission ack */ #ifndef HAVE_ENUM_MAV_MISSION_RESULT #define HAVE_ENUM_MAV_MISSION_RESULT -enum MAV_MISSION_RESULT -{ - MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ - MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */ - MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */ - MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */ - MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */ - MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */ - MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */ - MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */ - MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */ - MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */ - MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */ - MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */ - MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */ - MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */ - MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */ - MAV_MISSION_RESULT_ENUM_END=15, /* | */ -}; + enum MAV_MISSION_RESULT + { + MAV_MISSION_ACCEPTED = 0, /* mission accepted OK | */ + MAV_MISSION_ERROR = 1, /* generic error / not accepting mission commands at all right now | */ + MAV_MISSION_UNSUPPORTED_FRAME = 2, /* coordinate frame is not supported | */ + MAV_MISSION_UNSUPPORTED = 3, /* command is not supported | */ + MAV_MISSION_NO_SPACE = 4, /* mission item exceeds storage space | */ + MAV_MISSION_INVALID = 5, /* one of the parameters has an invalid value | */ + MAV_MISSION_INVALID_PARAM1 = 6, /* param1 has an invalid value | */ + MAV_MISSION_INVALID_PARAM2 = 7, /* param2 has an invalid value | */ + MAV_MISSION_INVALID_PARAM3 = 8, /* param3 has an invalid value | */ + MAV_MISSION_INVALID_PARAM4 = 9, /* param4 has an invalid value | */ + MAV_MISSION_INVALID_PARAM5_X = 10, /* x/param5 has an invalid value | */ + MAV_MISSION_INVALID_PARAM6_Y = 11, /* y/param6 has an invalid value | */ + MAV_MISSION_INVALID_PARAM7 = 12, /* param7 has an invalid value | */ + MAV_MISSION_INVALID_SEQUENCE = 13, /* received waypoint out of sequence | */ + MAV_MISSION_DENIED = 14, /* not accepting any mission commands from this communication partner | */ + MAV_MISSION_RESULT_ENUM_END = 15, /* | */ + }; #endif /** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */ #ifndef HAVE_ENUM_MAV_SEVERITY #define HAVE_ENUM_MAV_SEVERITY -enum MAV_SEVERITY -{ - MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */ - MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */ - MAV_SEVERITY_CRITICAL=2, /* Action must be taken immediately. Indicates failure in a primary system. | */ - MAV_SEVERITY_ERROR=3, /* Indicates an error in secondary/redundant systems. | */ - MAV_SEVERITY_WARNING=4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */ - MAV_SEVERITY_NOTICE=5, /* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */ - MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ - MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ - MAV_SEVERITY_ENUM_END=8, /* | */ -}; + enum MAV_SEVERITY + { + MAV_SEVERITY_EMERGENCY = 0, /* System is unusable. This is a "panic" condition. | */ + MAV_SEVERITY_ALERT = 1, /* Action should be taken immediately. Indicates error in non-critical systems. | */ + MAV_SEVERITY_CRITICAL = 2, /* Action must be taken immediately. Indicates failure in a primary system. | */ + MAV_SEVERITY_ERROR = 3, /* Indicates an error in secondary/redundant systems. | */ + MAV_SEVERITY_WARNING = 4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */ + MAV_SEVERITY_NOTICE = 5, /* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */ + MAV_SEVERITY_INFO = 6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ + MAV_SEVERITY_DEBUG = 7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ + MAV_SEVERITY_ENUM_END = 8, /* | */ + }; #endif // MESSAGE DEFINITIONS +#include "./mavlink_msg_homeposion.h" //自己添加的 用于获取返航点的 结构体 函数等 #include "./mavlink_msg_heartbeat.h" #include "./mavlink_msg_sys_status.h" #include "./mavlink_msg_system_time.h" diff --git a/src/FoodDeliveryBase.cpp b/src/FoodDeliveryBase.cpp index 315adb6..3282350 100644 --- a/src/FoodDeliveryBase.cpp +++ b/src/FoodDeliveryBase.cpp @@ -97,14 +97,6 @@ void FoodCube::logln(bool val) /** *@description: 取值 设置值 */ -bool FoodCube::getIsInit() -{ - return isInit; -} -void FoodCube::setIsInit(bool b) -{ - isInit = b; -} String FoodCube::getMacAdd() { return macAdd; @@ -564,6 +556,20 @@ void FoodCube::mav_parameter_data(const char *param_id) SWrite(buf, len, mavlinkSerial); } +/** + * @description: 向飞控请求返航点的位置数据 + */ +void FoodCube::mav_request_homePosition() +{ + mavlink_message_t msg; + uint8_t buf[MAVLINK_MAX_PACKET_LEN]; + + // 构造命令 MAV_CMD_GET_HOME_POSITION 请求 + mavlink_msg_command_long_pack(1, 200, &msg, 1, 1, MAV_CMD_GET_HOME_POSITION, 0, 0, 0, 0, 0, 0, 0, 0); + uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); + SWrite(buf, len, mavlinkSerial); +} + /** * @description: 解析mavlink数据流 * @param {pFun} pFun 拿到缓存数据之后 解析数据执行回调 diff --git a/src/FoodDeliveryBase.h b/src/FoodDeliveryBase.h index 183b6ce..eb0552a 100644 --- a/src/FoodDeliveryBase.h +++ b/src/FoodDeliveryBase.h @@ -16,6 +16,7 @@ #define MAVLINK_SYSTEM_ID 0xFF #define MAVLINK_COMPONENT_ID 0xBE + class FoodCube { public: @@ -42,8 +43,6 @@ public: void logln(IPAddress val); void logln(bool val); /*get set value*/ - bool getIsInit(); - void setIsInit(bool b); String getMacAdd(); /*wifi*/ void connectWifi(); @@ -64,7 +63,8 @@ public: /*mavlink*/ String setNBit(String str, uint8_t n, uint8_t i); void mav_request_data(); - void mav_parameter_data(const char* param_id); + void mav_parameter_data(const char *param_id); + void mav_request_homePosition(); void comm_receive(void (*pFun)(uint8_t)); void mav_mission_count(uint8_t taskcount); void mav_mission_item(int8_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, double param1, double param2, double param3, double param4, double x, double y, double z); @@ -89,7 +89,6 @@ private: char *mqttPassword; // mqtt密码 uint8_t mavlinkSerial; // 飞控占用的串口号 uint8_t voiceSerial; // 飞控占用的串口号 - bool isInit = true; // 用来判断接收到第一次心跳时 重新向飞控 发送一个请求数据类型 WiFiClient wifiClient; // 网络客户端 IPAddress localIp; // 板子的IP地址 diff --git a/src/commser.cpp b/src/commser.cpp index 7a1cc09..c50ffa9 100644 --- a/src/commser.cpp +++ b/src/commser.cpp @@ -34,8 +34,8 @@ uint32_t udpServerPort = 37260; // 云台相机端口 FoodCube fc(ssid, password, mqttServer, mqttPort, mqttName, mqttPassword, mavlinkSerial, voiceSerial, udpServerIP, udpServerPort); // 创建项目对象 /* 发布 主题 ps:以下是登记发布json内容的组成元素 */ // 登记 json成员名字 -// 0:心跳信息 1:电压信息 2:电流信息 3:电池电量 4:相对高度信息 5:对地速度 6:卫星数量 7:纬度 8:经度 9:定位状态 10:飞机状态 11:网速测试 12:飞机模式 13:重量 14:钩子状态 15:{经度,维度,海拔高度} 16:飞控参数{键:值} -const String topicPub[] = {"heartBeat", "voltagBattery", "currentBattery", "batteryRemaining", "positionAlt", "groundSpeed", "satCount", "latitude", "longitude", "fixType", "state", "pingNet", "getPlaneMode", "loadweight", "hookstatus", "position", "parameter"}; +// 0:心跳信息 1:电压信息 2:电流信息 3:电池电量 4:相对高度信息 5:对地速度 6:卫星数量 7:纬度 8:经度 9:定位状态 10:飞机状态 11:网速测试 12:飞机模式 13:重量 14:钩子状态 15:{经度,维度,海拔高度} 16:飞控参数{键:值} 17:返航点 +const String topicPub[] = {"heartBeat", "voltagBattery", "currentBattery", "batteryRemaining", "positionAlt", "groundSpeed", "satCount", "latitude", "longitude", "fixType", "state", "pingNet", "getPlaneMode", "loadweight", "hookstatus", "position", "parameter", "homePorsion"}; const int topicPubCount = sizeof(topicPub) / sizeof(topicPub[0]); // 登记 json成员总数 String topicPubMsg[topicPubCount] = {""}; // 登记 json成员的值 对应topicPub String oldMsg[topicPubCount] = {""}; // 记录旧的值 用来对比有没有更新 @@ -166,6 +166,10 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length) { fc.mav_parameter_data("BATT_CAPACITY"); // 请求飞控 返回参数 电池容量 值 } + else if (key == "getHomePorsion") + { + fc.mav_request_homePosition(); // 请求飞控返回 返航点 + } else if (key == "chan1") { uint16_t todo = value; // 转换值 @@ -524,6 +528,28 @@ void mavlink_receiveCallback(uint8_t c) } break; + case MAVLINK_MSG_ID_HOME_POSITION: // #242 返航点位置 + { + fc.pubMQTTmsg("demo", "homep"); + mavlink_home_position_t home_position; + mavlink_msg_home_position_decode(&msg, &home_position); + + // 提取经纬度并转换为度数 + double latitude = home_position.latitude / 1e7; + double longitude = home_position.longitude / 1e7; + + // 格式化为 JSON 字符串,包含经纬度 + sprintf(buf, "{\"lng\":%.7f,\"lat\":%.7f}", + longitude, latitude); + + // 更新 topicPubMsg 中的相关字段 + if (topicPubMsg[17] != buf) + { + topicPubMsg[17] = buf; + } + } + break; + case MAVLINK_MSG_ID_VFR_HUD: // #74 hud仪表盘 { mavlink_vfr_hud_t vfr_hud; @@ -584,7 +610,7 @@ void mavlink_receiveCallback(uint8_t c) break; case 4: { - topicPubMsg[9] = "Low GPS"; + topicPubMsg[9] = "DGPS"; // 不装rtk 最多到DGPS } break; case 5: @@ -711,26 +737,22 @@ void mavlink_receiveCallback(uint8_t c) */ void pubThread() { + /*检测飞控是否返回数据 (此处检测的电压字段) 没有数据 就像飞控请求*/ + if (topicPubMsg[1] == "") // 检测电压字段 + { + fc.mav_request_data(); // 请求 设定飞控输出数据流内容 + fc.mav_request_homePosition(); // 请求 飞控返航点 + fc.mav_parameter_data("BATT_CAPACITY"); // 请求飞控 返回参数 电池容量 值 + delay(100); + } /*解析mavlink 数据流等 此函数内会把解析的数据按信息类型 发布到mqtt服务器 planeState/macadd主题 */ // 创建一个JSON对象 DynamicJsonDocument doc(2000); // 缓冲区 // 遍历 有更新的数据 组成一个json对象 for (int i = 0; i < topicPubCount; i++) { - if (i == 0) - { // 心跳包 每每向心跳主题发布信息 - // 启动飞控 第一次心跳 ps:防止飞控 滞后启动 拿不到数据 - if (fc.getIsInit()) - { - fc.setIsInit(false); - fc.mav_request_data(); // 再向飞控请求一次 设定飞控输出数据流内容 - } - // 设置对象成员 ps:心跳 - doc[topicPub[i]] = topicPubMsg[i]; - } - else if (i == 3 || i == 10) + if (i == 0 || i == 10) // 0心跳包 10飞机状态state包 每每向心跳主题发布信息 { - // 设置对象成员 ps:3电池电量 10飞机状态state doc[topicPub[i]] = topicPubMsg[i]; } else if (topicPubMsg[i] != oldMsg[i]) @@ -748,14 +770,6 @@ void pubThread() // pingNetTest(); } -/** - * @description: 定时 指定飞控mavlink 串口返回的数据类别 防止飞控启动滞后 - */ -void mavThread() -{ - fc.mav_request_data(); -} - /** * @description: 向飞控 发送油门指令 */ diff --git a/src/commser.h b/src/commser.h index 7968105..53bf54c 100644 --- a/src/commser.h +++ b/src/commser.h @@ -7,7 +7,6 @@ #include "config.h" extern void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length); -extern void mavThread(); extern void pubThread(); extern void writeRoute(String topicStr); extern void mavlink_receiveCallback(uint8_t c); diff --git a/src/main.cpp b/src/main.cpp index 7eba8b6..dd13ba1 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -147,9 +147,8 @@ void setup() fc.mav_request_data(); // 指定飞控串口返回的数据类别(飞控启动之后发送才有意义) /*异步线程*/ - tksendinfo.attach(1, sendinfo); // 发送状态 - pubTicker.attach(1, pubThread); // 定时 发布主题 - mavTicker.attach(50, mavThread); // 定时 指定飞控mavlink 串口返回的数据类别 防止飞控启动滞后 + tksendinfo.attach(1, sendinfo); // 发送状态 + pubTicker.attach(1, pubThread); // 定时 发布主题 /////////////////////////////////MQTT_语音_MAVLINK 部分结束 // if (motocontrol.getstatus()==MS_Stop)