【类 型】:fix 改用 不检测是否数据是否更新 直接全部发送

【原  因】:解决控制端 或者 飞机掉线问题  保证数据最新 且同步
【过  程】:
【影  响】:

# 类型 包含:
# feat:新功能(feature)
# fix:修补bug
# docs:文档(documentation)
# style: 格式(不影响代码运行的变动)
# refactor:重构(即不是新增功能,也不是修改bug的代码变动)
# test:增加测试
# chore:构建过程或辅助工具的变动
This commit is contained in:
tk 2024-07-26 19:51:36 +08:00
parent ed39e11154
commit 816f3a4366
2 changed files with 6 additions and 37 deletions

View File

@ -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();
}
/**

View File

@ -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[];