【类 型】:fix 修改之前向飞控请求数据流的方式

【原  因】:(好处,不会有飞控滞后启动问题 不用一直发送请求)
【过  程】:老的方式:检测第一个心跳是 检测请求与否 没有就请求数据,另外每50秒强制请求一次。新的方式:检测电流字段是否赋过值 没有赋值就一直请求 直到收到飞控的数据流。
【影  响】:删掉之前相关的检测第一次发送状态的相关代码,删掉了每50秒请求的相关代码

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

File diff suppressed because one or more lines are too long

View File

@ -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

View File

@ -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地址

View File

@ -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:
*/

View File

@ -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);

View File

@ -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)