From 816f3a43664d60e39f704e4bb569f350f199a21b Mon Sep 17 00:00:00 2001 From: tk Date: Fri, 26 Jul 2024 19:51:36 +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=E6=94=B9=E7=94=A8=20=E4=B8=8D=E6=A3=80=E6=B5=8B?= =?UTF-8?q?=E6=98=AF=E5=90=A6=E6=95=B0=E6=8D=AE=E6=98=AF=E5=90=A6=E6=9B=B4?= =?UTF-8?q?=E6=96=B0=20=20=E7=9B=B4=E6=8E=A5=E5=85=A8=E9=83=A8=E5=8F=91?= =?UTF-8?q?=E9=80=81=20=E3=80=90=E5=8E=9F=20=20=E5=9B=A0=E3=80=91=EF=BC=9A?= =?UTF-8?q?=E8=A7=A3=E5=86=B3=E6=8E=A7=E5=88=B6=E7=AB=AF=20=E6=88=96?= =?UTF-8?q?=E8=80=85=20=E9=A3=9E=E6=9C=BA=E6=8E=89=E7=BA=BF=E9=97=AE?= =?UTF-8?q?=E9=A2=98=20=20=E4=BF=9D=E8=AF=81=E6=95=B0=E6=8D=AE=E6=9C=80?= =?UTF-8?q?=E6=96=B0=20=E4=B8=94=E5=90=8C=E6=AD=A5=20=E3=80=90=E8=BF=87=20?= =?UTF-8?q?=20=E7=A8=8B=E3=80=91=EF=BC=9A=20=E3=80=90=E5=BD=B1=20=20?= =?UTF-8?q?=E5=93=8D=E3=80=91=EF=BC=9A?= 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:构建过程或辅助工具的变动 --- src/commser.cpp | 42 ++++++------------------------------------ src/commser.h | 1 - 2 files changed, 6 insertions(+), 37 deletions(-) diff --git a/src/commser.cpp b/src/commser.cpp index f5de8e9..d331de6 100644 --- a/src/commser.cpp +++ b/src/commser.cpp @@ -38,7 +38,6 @@ FoodCube fc(ssid, password, mqttServer, mqttPort, mqttName, mqttPassword, mavlin 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] = {""}; // 记录旧的值 用来对比有没有更新 /*触发发送 主题*/ // 0:对频信息 String topicHandle[] = {"crosFrequency"}; @@ -153,10 +152,6 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length) fc.mav_command(n, param); } } - else if (key == "getPlaneState") // 终端主动get飞机状态 - { - forcePubMsg(); // 强制发送飞机 现在的所有状态值 - } else if (key == "resetState") { // 恢复飞机为初始状态 String todo = value; // 转换值 @@ -732,41 +727,14 @@ void pubThread() /*检测飞控是否返回数据 (此处检测的电压字段) 没有数据 就像飞控请求*/ if (topicPubMsg[1] == "") // 检测电压字段 { - fc.mav_request_data(); // 请求 设定飞控输出数据流内容 - fc.mav_request_homePosition(); // 请求 飞控返航点 + fc.mav_request_data(); // 请求 设定飞控输出数据流内容 + delay(100); + fc.mav_request_homePosition(); // 请求 飞控返航点 + delay(100); 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 || i == 10) // 0心跳包 10飞机状态state包 每每向心跳主题发布信息 - { - doc[topicPub[i]] = topicPubMsg[i]; - } - else if (topicPubMsg[i] != oldMsg[i]) - { - // 非心跳 非飞机状态 有更新 录入成员 - doc[topicPub[i]] = topicPubMsg[i]; - oldMsg[i] = topicPubMsg[i]; - } - } - // 将JSON对象序列化为JSON字符串 - String jsonString; - serializeJson(doc, jsonString); - fc.pubMQTTmsg("planeState", jsonString); - /*更新4G网络测速ping值*/ - // pingNetTest(); -} - -/** - * @description: 强制遍历发送主题线程 ps:不管内容如何哪怕是空字符 - */ -void forcePubMsg() -{ // 创建一个JSON对象 DynamicJsonDocument doc(2000); // 缓冲区 // 遍历 有更新的数据 组成一个json对象 @@ -778,6 +746,8 @@ void forcePubMsg() String jsonString; serializeJson(doc, jsonString); fc.pubMQTTmsg("planeState", jsonString); + /*更新4G网络测速ping值*/ + // pingNetTest(); } /** diff --git a/src/commser.h b/src/commser.h index d7bd6dc..53bf54c 100644 --- a/src/commser.h +++ b/src/commser.h @@ -8,7 +8,6 @@ extern void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length); extern void pubThread(); -extern void forcePubMsg(); extern void writeRoute(String topicStr); extern void mavlink_receiveCallback(uint8_t c); extern const String topicPub[];