【类 型】:fix
【主 题】:修复bug 【描 述】: [原因]:不需要订阅多主题 制定粤'cmd/macadd' 参数的主题数组就不需要了 [过程]:mqtt订阅函数参数删除 ;维持心跳函数 参数删除 [影响]: 【结 束】 # 类型 包含: # feat:新功能(feature) # fix:修补bug # docs:文档(documentation) # style: 格式(不影响代码运行的变动) # refactor:重构(即不是新增功能,也不是修改bug的代码变动) # test:增加测试 # chore:构建过程或辅助工具的变动
This commit is contained in:
parent
b708b47c4b
commit
db3e2ec931
@ -38,7 +38,7 @@ void setup() {
|
|||||||
Serial1.begin(115200, SERIAL_8N1, 18, 5); //声音模块引串口脚映射
|
Serial1.begin(115200, SERIAL_8N1, 18, 5); //声音模块引串口脚映射
|
||||||
/*初始化*/
|
/*初始化*/
|
||||||
fc.connectWifi(); //连接wifi
|
fc.connectWifi(); //连接wifi
|
||||||
fc.connectMqtt(topicSub, topicSubCount); //连接mqtt
|
fc.connectMqtt("cmd"); //连接mqtt
|
||||||
fc.mqttClient->setCallback(mqtt_receiveCallback); //设置订阅成功 回调
|
fc.mqttClient->setCallback(mqtt_receiveCallback); //设置订阅成功 回调
|
||||||
fc.mav_request_data(); //指定飞控串口返回的数据类别(飞控启动之后发送才有意义)
|
fc.mav_request_data(); //指定飞控串口返回的数据类别(飞控启动之后发送才有意义)
|
||||||
|
|
||||||
@ -54,7 +54,7 @@ void loop() {
|
|||||||
/*从飞控拿数据*/
|
/*从飞控拿数据*/
|
||||||
fc.comm_receive(mavlink_receiveCallback);
|
fc.comm_receive(mavlink_receiveCallback);
|
||||||
/*保持mqtt心跳*/
|
/*保持mqtt心跳*/
|
||||||
fc.mqttLoop(topicSub, topicSubCount);
|
fc.mqttLoop("cmd");
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -202,7 +202,7 @@ void mqtt_receiveCallback(char* topic, byte* payload, unsigned int length) {
|
|||||||
//相机控制
|
//相机控制
|
||||||
if (item == 0) { //0:一键回中
|
if (item == 0) { //0:一键回中
|
||||||
uint8_t stopCommand[] = { 0x55, 0x66, 0x01, 0x02, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00 }; //回中前 强制 俯仰旋转 停止
|
uint8_t stopCommand[] = { 0x55, 0x66, 0x01, 0x02, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00 }; //回中前 强制 俯仰旋转 停止
|
||||||
size_t stopLen = sizeof(StopCommand);
|
size_t stopLen = sizeof(stopCommand);
|
||||||
fc.udpSendToCamera(stopCommand, stopLen);
|
fc.udpSendToCamera(stopCommand, stopLen);
|
||||||
uint8_t command[] = { 0x55, 0x66, 0x01, 0x01, 0x00, 0x00, 0x00, 0x08, 0x01 };
|
uint8_t command[] = { 0x55, 0x66, 0x01, 0x01, 0x00, 0x00, 0x00, 0x08, 0x01 };
|
||||||
size_t len = sizeof(command);
|
size_t len = sizeof(command);
|
||||||
@ -220,7 +220,7 @@ void mqtt_receiveCallback(char* topic, byte* payload, unsigned int length) {
|
|||||||
fc.udpSendToCamera(command, len);
|
fc.udpSendToCamera(command, len);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
/**
|
/**
|
||||||
* @description: 写入航点
|
* @description: 写入航点
|
||||||
* @param {String} todo mqtt订阅执行任务的Json字符串
|
* @param {String} todo mqtt订阅执行任务的Json字符串
|
||||||
@ -234,7 +234,7 @@ void mqtt_receiveCallback(char* topic, byte* payload, unsigned int length) {
|
|||||||
//改变飞机状态 PS:mqtt发送写在这里 同步执行下面while循环时 写在loop函数里面 不会被执行到
|
//改变飞机状态 PS:mqtt发送写在这里 同步执行下面while循环时 写在loop函数里面 不会被执行到
|
||||||
topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 1, 1); //正在写入航点
|
topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 1, 1); //正在写入航点
|
||||||
topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 0, 0); //结束初始状态
|
topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 0, 0); //结束初始状态
|
||||||
fc.pubMQTTmsg("planeState", "{\"state\":" + topicPubMsg[10] + "}")//发送正在写入的飞机状态
|
fc.pubMQTTmsg("planeState", "{\"state\":" + topicPubMsg[10] + "}"); //发送正在写入的飞机状态
|
||||||
// json 反序列化
|
// json 反序列化
|
||||||
DynamicJsonDocument doc(0x2FFF);
|
DynamicJsonDocument doc(0x2FFF);
|
||||||
deserializeJson(doc, todoJson);
|
deserializeJson(doc, todoJson);
|
||||||
@ -291,7 +291,6 @@ void mqtt_receiveCallback(char* topic, byte* payload, unsigned int length) {
|
|||||||
delay(200);
|
delay(200);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @description: 从串口拿到mavlink缓存数据之后 解析数据执行的回调
|
* @description: 从串口拿到mavlink缓存数据之后 解析数据执行的回调
|
||||||
* @param {mavlink_message_t*} pMsg mavlink数据信息指针
|
* @param {mavlink_message_t*} pMsg mavlink数据信息指针
|
||||||
@ -539,7 +538,6 @@ void mqtt_receiveCallback(char* topic, byte* payload, unsigned int length) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @description: 发送主题线程
|
* @description: 发送主题线程
|
||||||
*/
|
*/
|
||||||
|
@ -121,10 +121,9 @@ void FoodCube::connectWifi() {
|
|||||||
|
|
||||||
/**
|
/**
|
||||||
* @description: 连接mqtt
|
* @description: 连接mqtt
|
||||||
* @param {String[]} topicSub 主题数组
|
* @param {String} topicSub 订阅主题
|
||||||
* @param {int} topicSubCount 数组总数
|
|
||||||
*/
|
*/
|
||||||
void FoodCube::connectMqtt(String topicSub[], int topicSubCount) {
|
void FoodCube::connectMqtt(String topicSub) {
|
||||||
/*尝试连接mqtt*/
|
/*尝试连接mqtt*/
|
||||||
if (mqttClient->connect(macAdd.c_str(), mqttName, mqttPassword)) {
|
if (mqttClient->connect(macAdd.c_str(), mqttName, mqttPassword)) {
|
||||||
logln("MQTT Server Connected.");
|
logln("MQTT Server Connected.");
|
||||||
@ -134,7 +133,7 @@ void FoodCube::connectMqtt(String topicSub[], int topicSubCount) {
|
|||||||
logln(macAdd);
|
logln(macAdd);
|
||||||
/*连接成功 订阅主题*/
|
/*连接成功 订阅主题*/
|
||||||
//订阅主题 PS:连接上mqtt服务器 订阅主题 收到信息触发回调函数 receiveCallback
|
//订阅主题 PS:连接上mqtt服务器 订阅主题 收到信息触发回调函数 receiveCallback
|
||||||
subscribeTopic("cmd", 1);
|
subscribeTopic(topicSub, 1);
|
||||||
playText("服务器,已连接");
|
playText("服务器,已连接");
|
||||||
} else {
|
} else {
|
||||||
//失败返回状态码
|
//失败返回状态码
|
||||||
@ -146,14 +145,13 @@ void FoodCube::connectMqtt(String topicSub[], int topicSubCount) {
|
|||||||
|
|
||||||
/**
|
/**
|
||||||
* @description: 写在loop函数里 检测mqtt连接情况 并保持心跳
|
* @description: 写在loop函数里 检测mqtt连接情况 并保持心跳
|
||||||
* @param {String[]} topicSub 主题数组
|
* @param {String} topicSub 订阅主题
|
||||||
* @param {int} topicSubCount 数组总数
|
|
||||||
*/
|
*/
|
||||||
void FoodCube::mqttLoop(String topicSub[], int topicSubCount) {
|
void FoodCube::mqttLoop(String topicSub) {
|
||||||
if (mqttClient->connected()) { //检测 如果开发板成功连接服务器
|
if (mqttClient->connected()) { //检测 如果开发板成功连接服务器
|
||||||
mqttClient->loop(); // 保持心跳
|
mqttClient->loop(); // 保持心跳
|
||||||
} else { // 如果开发板未能成功连接服务器
|
} else { // 如果开发板未能成功连接服务器
|
||||||
connectMqtt(topicSub, topicSubCount); // 则尝试连接服务器
|
connectMqtt(topicSub); // 则尝试连接服务器
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -46,8 +46,8 @@ public:
|
|||||||
void connectWifi();
|
void connectWifi();
|
||||||
/*mqtt*/
|
/*mqtt*/
|
||||||
PubSubClient* mqttClient; //指向 mqtt服务器连接 对象
|
PubSubClient* mqttClient; //指向 mqtt服务器连接 对象
|
||||||
void connectMqtt(String topicSub[], int topicSubCount);
|
void connectMqtt(String topicSub);
|
||||||
void mqttLoop(String topicSub[], int topicSubCount);
|
void mqttLoop(String topicSub);
|
||||||
void subscribeTopic(String topicString, int Qos);
|
void subscribeTopic(String topicString, int Qos);
|
||||||
void pubMQTTmsg(String topicString, String messageString);
|
void pubMQTTmsg(String topicString, String messageString);
|
||||||
/*串口输出*/
|
/*串口输出*/
|
||||||
|
Loading…
Reference in New Issue
Block a user