【类 型】:fix 1pubThread发送主题对比有信息 再发 2.请求home点函数 发送求情命令失败
【原 因】:1.减小发送数据量 前端可以按需请求 2.多了两个参数 【过 程】: 【影 响】:
This commit is contained in:
parent
d200fc0f46
commit
8109c74062
@ -566,8 +566,6 @@ void FoodCube::mav_request_home_position()
|
||||
|
||||
// 组装命令
|
||||
mavlink_command_long_t command = {0};
|
||||
command.target_system = 1; // 目标飞控的系统ID
|
||||
command.target_component = 1; // 目标飞控的组件ID
|
||||
command.command = MAV_CMD_GET_HOME_POSITION;
|
||||
command.confirmation = 0;
|
||||
command.param1 = 0; // 参数保留,不使用
|
||||
@ -579,7 +577,7 @@ void FoodCube::mav_request_home_position()
|
||||
command.param7 = 0;
|
||||
|
||||
// 打包命令消息
|
||||
mavlink_msg_command_long_encode(1, 1, &msg, &command);
|
||||
mavlink_msg_command_long_encode(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, &command);
|
||||
|
||||
// 将消息转换为字节流并发送
|
||||
int len = mavlink_msg_to_send_buffer(buf, &msg);
|
||||
|
@ -364,6 +364,7 @@ void mavlink_receiveCallback(uint8_t c)
|
||||
char buf[10];
|
||||
|
||||
// printf("mav_id:%d\n",msg.msgid);
|
||||
fc.pubMQTTmsg("test", String(msg.msgid));
|
||||
|
||||
switch (msg.msgid)
|
||||
{
|
||||
@ -734,8 +735,8 @@ void mavlink_receiveCallback(uint8_t c)
|
||||
*/
|
||||
void pubThread()
|
||||
{
|
||||
/*检测飞控是否返回数据 (此处检测的电压字段) 没有数据 就像飞控请求*/
|
||||
if (topicPubMsg[1] == "") // 检测电压字段
|
||||
/*检测飞控是否返回数据 (此处检测的心跳字段) 没有数据 就像飞控请求*/
|
||||
if (topicPubMsg[0] == "") // 检测心跳字段
|
||||
{
|
||||
refreshRequest();
|
||||
}
|
||||
@ -745,7 +746,18 @@ void pubThread()
|
||||
// 遍历 有更新的数据 组成一个json对象
|
||||
for (int i = 0; i < topicPubCount; i++)
|
||||
{
|
||||
doc[topicPub[i]] = topicPubMsg[i];
|
||||
if (i == 0) // 心跳每次发 需要每次必发的写在这里
|
||||
{
|
||||
doc[topicPub[i]] = topicPubMsg[i];
|
||||
}
|
||||
else // 其余有新值就发
|
||||
{
|
||||
if (topicPubMsg[i] != "")
|
||||
{
|
||||
doc[topicPub[i]] = topicPubMsg[i];
|
||||
topicPubMsg[i] = "";
|
||||
}
|
||||
}
|
||||
}
|
||||
// fc.mav_request_home_position(); // 请求 飞控返航点
|
||||
// 将JSON对象序列化为JSON字符串
|
||||
|
Loading…
Reference in New Issue
Block a user