Compare commits

...

7 Commits

Author SHA1 Message Date
air
00120883af 【类 型】:test
【原  因】:尝试解决 新的mqtt库导致的主核心卡顿问题(4-5十毫秒延迟) ,此本版为解决卡顿
【过  程】:
【影  响】:
2025-06-06 14:48:12 +08:00
3445924e10 【类 型】:test
【原  因】:loop函数 逐行检测运行时长
【过  程】:
【影  响】:

# 类型 包含:
# feat:新功能(feature)
# fix:修补bug
# docs:文档(documentation)
# style: 格式(不影响代码运行的变动)
# refactor:重构(即不是新增功能,也不是修改bug的代码变动)
# test:增加测试
# chore:构建过程或辅助工具的变动
2025-05-24 16:06:47 +08:00
air
db87abadb5 【类 型】:test
【原  因】:测试 主核心延迟大原因
【过  程】:初始化wifi 发送请求数据类别到飞控串口  异步发送窗台 发布飞机状态主题 移至 副核心上运行
【影  响】:

# 类型 包含:
# feat:新功能(feature)
# fix:修补bug
# docs:文档(documentation)
# style: 格式(不影响代码运行的变动)
# refactor:重构(即不是新增功能,也不是修改bug的代码变动)
# test:增加测试
# chore:构建过程或辅助工具的变动
2025-05-23 19:35:39 +08:00
air
02c767bdf4 【类 型】:test
【原  因】:
【过  程】:
【影  响】:

# 类型 包含:
# feat:新功能(feature)
# fix:修补bug
# docs:文档(documentation)
# style: 格式(不影响代码运行的变动)
# refactor:重构(即不是新增功能,也不是修改bug的代码变动)
# test:增加测试
# chore:构建过程或辅助工具的变动
2025-05-23 18:48:58 +08:00
air
20b6440554 【类 型】:refactor
【原  因】:mqtt不能发送Qos参数
【过  程】:改为使用AsyncMqttClient 库
【影  响】:

# 类型 包含:
# feat:新功能(feature)
# fix:修补bug
# docs:文档(documentation)
# style: 格式(不影响代码运行的变动)
# refactor:重构(即不是新增功能,也不是修改bug的代码变动)
# test:增加测试
# chore:构建过程或辅助工具的变动
2025-05-23 18:14:19 +08:00
air
05f145324e 【类 型】:
【原  因】:
【过  程】:
【影  响】:

# 类型 包含:
# feat:新功能(feature)
# fix:修补bug
# docs:文档(documentation)
# style: 格式(不影响代码运行的变动)
# refactor:重构(即不是新增功能,也不是修改bug的代码变动)
# test:增加测试
# chore:构建过程或辅助工具的变动
2025-05-23 14:01:25 +08:00
air
7b4c812f96 【类 型】:feat
【原  因】:添加AsyncMqttClient库
【过  程】:
【影  响】:

# 类型 包含:
# feat:新功能(feature)
# fix:修补bug
# docs:文档(documentation)
# style: 格式(不影响代码运行的变动)
# refactor:重构(即不是新增功能,也不是修改bug的代码变动)
# test:增加测试
# chore:构建过程或辅助工具的变动
2025-05-23 11:14:02 +08:00
7 changed files with 260 additions and 156 deletions

View File

@ -21,3 +21,4 @@ lib_deps =
fastled/FastLED@^3.5.0 fastled/FastLED@^3.5.0
madhephaestus/ESP32Servo@^0.13.0 madhephaestus/ESP32Servo@^0.13.0
sandeepmistry/CAN@^0.3.1 sandeepmistry/CAN@^0.3.1
marvinroger/AsyncMqttClient@^0.9.0

View File

@ -5,7 +5,7 @@
* @description: * @description:
*/ */
static const char *MOUDLENAME = "FC"; static const char *MOUDLENAME = "FC";
FoodCube::FoodCube(char *userSsid, char *userPassword, char *userMqttServer, int userMqttPort, char *userMqttName, char *userMqttPassword, uint8_t userMavlinkSerial, uint8_t userVoiceSerial, char *userUdpServerIP, uint32_t userUdpServerPort) FoodCube::FoodCube(const char *userSsid, const char *userPassword, const char *userMqttServer, int userMqttPort, const char *userMqttName, const char *userMqttPassword, String userMqttTopic, uint8_t userMavlinkSerial, uint8_t userVoiceSerial, const char *userUdpServerIP, uint32_t userUdpServerPort)
{ {
/*初始化*/ /*初始化*/
ssid = userSsid; // wifi帐号 ssid = userSsid; // wifi帐号
@ -14,6 +14,7 @@ FoodCube::FoodCube(char *userSsid, char *userPassword, char *userMqttServer, int
mqttPort = userMqttPort; // mqtt服务器端口 mqttPort = userMqttPort; // mqtt服务器端口
mqttName = userMqttName; // mqtt帐号 mqttName = userMqttName; // mqtt帐号
mqttPassword = userMqttPassword; // mqtt密码 mqttPassword = userMqttPassword; // mqtt密码
mqttTopic = userMqttTopic; // mqtt主题
mavlinkSerial = userMavlinkSerial; // mavlink用的串口 mavlinkSerial = userMavlinkSerial; // mavlink用的串口
voiceSerial = userVoiceSerial; // 声音模块用的串口 voiceSerial = userVoiceSerial; // 声音模块用的串口
udpServerIP = userUdpServerIP; // 云台相机ip udpServerIP = userUdpServerIP; // 云台相机ip
@ -54,8 +55,19 @@ FoodCube::FoodCube(char *userSsid, char *userPassword, char *userMqttServer, int
break; break;
} }
/*初始化 连接mqtt对象 赋予mqttClient指针*/ /*初始化 连接mqtt对象 赋予mqttClient指针*/
mqttClient = new PubSubClient(mqttServer, mqttPort, wifiClient); mqttClient = new AsyncMqttClient();
SetplayvolMax(); mqttClient->setServer(mqttServer, mqttPort);
mqttClient->setCredentials(mqttName, mqttPassword);
}
/*析构*/
FoodCube::~FoodCube()
{
/*释放mqttClient*/
if (mqttClient != nullptr)
{
delete mqttClient;
mqttClient = nullptr;
}
} }
/** /**
* @description: * @description:
@ -65,7 +77,7 @@ void FoodCube::log(String val)
{ {
Serial.print(val); Serial.print(val);
} }
void FoodCube::log(char *val) void FoodCube::log(const char *val)
{ {
Serial.print(val); Serial.print(val);
} }
@ -85,7 +97,7 @@ void FoodCube::logln(String val)
{ {
ESP_LOGD(MOUDLENAME, "%s", val); ESP_LOGD(MOUDLENAME, "%s", val);
} }
void FoodCube::logln(char *val) void FoodCube::logln(const char *val)
{ {
ESP_LOGD(MOUDLENAME, "%s", val); ESP_LOGD(MOUDLENAME, "%s", val);
} }
@ -136,10 +148,10 @@ bool FoodCube::checkWiFiStatus()
{ {
wificonnected = true; wificonnected = true;
// 获取局域网ip // 获取局域网ip
logln(""); // logln("");
logln("WiFi connected"); // logln("WiFi connected");
log("IP address: "); // log("IP address: ");
logln(WiFi.localIP()); // logln(WiFi.localIP());
localIp = WiFi.localIP(); localIp = WiFi.localIP();
// 设置开发板为无线终端 获取物理mac地址 // 设置开发板为无线终端 获取物理mac地址
WiFi.mode(WIFI_STA); WiFi.mode(WIFI_STA);
@ -151,58 +163,6 @@ bool FoodCube::checkWiFiStatus()
} }
return wificonnected; return wificonnected;
} }
/**
* @description: mqtt
* @param {String} topicSub
*/
void FoodCube::connectMqtt(String topicSub)
{
if (mqttClient->connected())
return;
/*尝试连接mqtt*/
if ((millis() - _tm_mqttconnect) > 3000)
{
logln("connect_mqtt");
if (mqttClient->connect(macAdd.c_str(), mqttName, mqttPassword))
{
logln("MQTT Server Connected.");
log("Server Address: ");
logln(mqttServer);
log("ClientId :");
logln(macAdd);
/*连接成功 订阅主题*/
// 订阅主题 PS:连接上mqtt服务器 订阅主题 收到信息触发回调函数 receiveCallback
subscribeTopic(topicSub, 1);
delay(500);
playText("服务器已连接");
}
else
{
// 失败返回状态码
log("MQTT Server Connect Failed. Client State:");
logln(mqttClient->state());
_tm_mqttconnect = millis();
playText("服务器断开尝试重新连接");
// delay(3000);
}
}
}
/**
* @description: loop函数里 mqtt连接情况
* @param {String} topicSub
*/
void FoodCube::mqttLoop(String topicSub)
{
if (mqttClient->connected())
{ // 检测 如果开发板成功连接服务器
mqttClient->loop(); // 保持心跳
}
else
{ // 如果开发板未能成功连接服务器
connectMqtt(topicSub); // 则尝试连接服务器
}
}
/** /**
* @description: * @description:
@ -220,21 +180,23 @@ void FoodCube::subscribeTopic(String topicString, int Qos = 1)
} }
/** /**
* @description: * @brief AsyncMqttClient QoS
* @param {String} topicString *
* @param {String} messageString * @param topicString MQTT主题名称MAC后缀
* @param messageString
* @param qos QoS等级0, 1 2012()
*/ */
void FoodCube::pubMQTTmsg(String topicString, String messageString) void FoodCube::pubMQTTmsg(String topicString, String messageString, uint8_t Qos)
{ {
// 处理主题字符串 // 构造完整主题拼接设备MAC地址
topicString = topicString + "/" + macAdd; topicString = topicString + "/" + macAdd;
char publishTopic[topicString.length() + 1];
strcpy(publishTopic, topicString.c_str()); // 转换为 const char*,适配 AsyncMqttClient 接口
// 处理发布内容字符串 const char *publishTopic = topicString.c_str();
char publishMsg[messageString.length() + 1]; const char *publishMsg = messageString.c_str();
strcpy(publishMsg, messageString.c_str());
// 向指定主题 发布信息 // 发布消息retain 为 false可按需修改
mqttClient->publish(publishTopic, publishMsg); mqttClient->publish(publishTopic, Qos, false, publishMsg);
} }
/** /**
@ -796,12 +758,12 @@ void FoodCube::sendSetPositionTargetGlobalInt(double lat_deg, double lon_deg, do
// 设置 type_mask仅启用位置控制字段其它字段被忽略 // 设置 type_mask仅启用位置控制字段其它字段被忽略
sp.type_mask = sp.type_mask =
(1 << 1) | // 忽略 vx (1 << 3) | // 忽略 vx
(1 << 2) | // 忽略 vy (1 << 4) | // 忽略 vy
(1 << 3) | // 忽略 vz (1 << 5) | // 忽略 vz
(1 << 4) | // 忽略 afx (1 << 6) | // 忽略 afx
(1 << 5) | // 忽略 afy (1 << 7) | // 忽略 afy
(1 << 6) | // 忽略 afz (1 << 8) | // 忽略 afz
(1 << 10) | // 忽略 yaw (1 << 10) | // 忽略 yaw
(1 << 11); // 忽略 yaw_rate (1 << 11); // 忽略 yaw_rate

View File

@ -4,7 +4,8 @@
/*wifi*/ /*wifi*/
#include "WiFi.h" #include "WiFi.h"
/*mqtt*/ /*mqtt*/
#include "PubSubClient.h" #include "AsyncMqttClient.h"
/*mavlink*/ /*mavlink*/
#include "../lib/mavlink/ardupilotmega/mavlink.h" #include "../lib/mavlink/ardupilotmega/mavlink.h"
#include "../lib/mavlink/common/mavlink.h" #include "../lib/mavlink/common/mavlink.h"
@ -33,29 +34,32 @@ public:
/*前端模拟遥控的油门通道*/ /*前端模拟遥控的油门通道*/
uint16_t channels[4] = {1500, 1500, 1500, 1500}; uint16_t channels[4] = {1500, 1500, 1500, 1500};
/*初始化*/ /*初始化*/
FoodCube(char *userSsid, char *userPassword, char *userMqttServer, int userMqttPort, char *userMqttName, char *userMqttPassword, uint8_t userMavlinkSerial, uint8_t userVoiceSerial, char *userUdpServerIP, uint32_t userUdpServerPort); FoodCube(const char *userSsid, const char *userPassword, const char *userMqttServer, int userMqttPort, const char *userMqttName, const char *userMqttPassword, String userMqttTopic, uint8_t userMavlinkSerial, uint8_t userVoiceSerial, const char *userUdpServerIP, uint32_t userUdpServerPort);
~FoodCube();
/*日志打印*/ /*日志打印*/
void log(String val); void log(String val);
void log(char *val); void log(const char *val);
void log(int val); void log(int val);
void log(IPAddress val); void log(IPAddress val);
void log(bool val); void log(bool val);
void logln(String val); void logln(String val);
void logln(char *val); void logln(const char *val);
void logln(int val); void logln(int val);
void logln(IPAddress val); void logln(IPAddress val);
void logln(bool val); void logln(bool val);
/*get set value*/ /*get set value*/
String getMacAdd(); String getMacAdd();
/*wifi*/ /*wifi*/
String macAdd; // 板子的物理地址(已去掉冒号分隔符)
void connectWifi(); void connectWifi();
bool checkWiFiStatus(); bool checkWiFiStatus();
/*mqtt*/ /*mqtt*/
PubSubClient *mqttClient; // 指向 mqtt服务器连接 对象 String mqttTopic; // 订阅mqtt主题
AsyncMqttClient *mqttClient; // 指向 mqtt服务器连接 对象
void connectMqtt(String topicSub); void connectMqtt(String topicSub);
void mqttLoop(String topicSub); 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, uint8_t qos);
/*声音模块控制*/ /*声音模块控制*/
// 枚举,音量 // 枚举,音量
@ -100,22 +104,23 @@ public:
void Camera_action_zoom(uint8_t vzoom); void Camera_action_zoom(uint8_t vzoom);
private: private:
char *ssid; // wifi帐号 const char *ssid; // wifi帐号
char *password; // wifi密码 const char *password; // wifi密码
char *mqttServer; // mqtt服务器地址 const char *mqttServer; // mqtt服务器地址
int mqttPort; // mqtt服务器端口 int mqttPort; // mqtt服务器端口
char *mqttName; // mqtt帐号 const char *mqttName; // mqtt帐号
char *mqttPassword; // mqtt密码 const char *mqttPassword; // mqtt密码
uint8_t mavlinkSerial; // 飞控占用的串口号 uint8_t mavlinkSerial; // 飞控占用的串口号
uint8_t voiceSerial; // 飞控占用的串口号 uint8_t voiceSerial; // 飞控占用的串口号
WiFiClient wifiClient; // 网络客户端 WiFiClient wifiClient; // 网络客户端
IPAddress localIp; // 板子的IP地址 IPAddress localIp; // 板子的IP地址
String macAdd; // 板子的物理地址(已去掉冒号分隔符)
bool wificonnected; // 网络是否连接 bool wificonnected; // 网络是否连接
/*云台相机控制*/ /*云台相机控制*/
WiFiUDP udp; // udp信息操作对象 WiFiUDP udp; // udp信息操作对象
char *udpServerIP; // 云台相机ip地址 const char *udpServerIP; // 云台相机ip地址
uint32_t udpServerPort; // 云台相机端口 uint32_t udpServerPort; // 云台相机端口
unsigned long _tm_mqttconnect; // mqtt上次连接时间 unsigned long _tm_mqttconnect; // mqtt上次连接时间

View File

@ -22,18 +22,19 @@ static const char *MOUDLENAME = "COMMSER";
// char* password = "63587839ab"; //wifi密码 // char* password = "63587839ab"; //wifi密码
// char *ssid = "flicube"; // wifi帐号 // char *ssid = "flicube"; // wifi帐号
// char *password = "fxmf0622"; // wifi密码 // char *password = "fxmf0622"; // wifi密码
char *ssid = "fxmf_sc02"; // 4g wifi帐号 const char *ssid = "fxmf_sc02"; // 4g wifi帐号
char *password = "12345678"; // 4g wifi密码 const char *password = "12345678"; // 4g wifi密码
char *mqttServer = "szdot.top"; // mqtt地址 const char *mqttServer = "szdot.top"; // mqtt地址
int mqttPort = 1883; // mqtt端口 int mqttPort = 1883; // mqtt端口
char *mqttName = "admin"; // mqtt帐号 const char *mqttName = "admin"; // mqtt帐号
char *mqttPassword = "123456"; // mqtt密码 const char *mqttPassword = "123456"; // mqtt密码
uint8_t mavlinkSerial = 2; // 飞控占用的串口号 String mqttTopic = "cmd"; // mqtt主题前缀 (cmd/macAdd)
uint8_t voiceSerial = 1; // 声音模块占用串口 uint8_t mavlinkSerial = 2; // 飞控占用的串口号
char *udpServerIP = "192.168.3.92"; // 云台相机ip uint8_t voiceSerial = 1; // 声音模块占用串口
uint32_t udpServerPort = 37260; // 云台相机端口 const char *udpServerIP = "192.168.3.92"; // 云台相机ip
uint32_t udpServerPort = 37260; // 云台相机端口
FoodCube fc(ssid, password, mqttServer, mqttPort, mqttName, mqttPassword, mavlinkSerial, voiceSerial, udpServerIP, udpServerPort); // 创建项目对象 FoodCube fc(ssid, password, mqttServer, mqttPort, mqttName, mqttPassword, mqttTopic, mavlinkSerial, voiceSerial, udpServerIP, udpServerPort); // 创建项目对象
/* 发布 主题 ps:以下是登记发布json内容的组成元素 */ /* 发布 主题 ps:以下是登记发布json内容的组成元素 */
// 登记 json成员名字 // 登记 json成员名字
@ -66,6 +67,61 @@ Ticker mavTicker; // 定时 指定飞控mavlink 串口返回的数据类别 防
Ticker funTicker; // 延迟执行 Ticker funTicker; // 延迟执行
// Ticker chanTicker; //定时向飞控 发送油门指定 // Ticker chanTicker; //定时向飞控 发送油门指定
portMUX_TYPE espMutex = portMUX_INITIALIZER_UNLOCKED; portMUX_TYPE espMutex = portMUX_INITIALIZER_UNLOCKED;
/**
* @brief MQTT消息接收回调
*
*
* mqtt_receiveCallback
*
* @param topic MQTT主题字符串
* @param payload
* @param properties MQTT消息属性使
* @param len
* @param index
* @param total
*/
void async_mqtt_receiveCallback(char *topic, char *payload, AsyncMqttClientMessageProperties properties,
size_t len, size_t index, size_t total)
{
static uint8_t buffer[2048]; // 静态缓存区,存放整条消息,大小需根据最大消息长度调整
static size_t expected_total = 0; // 记录期望接收的完整消息长度
// 如果是新消息开始(第一个分片)
if (index == 0)
{
expected_total = total; // 记录当前消息总长度
// 检查消息长度是否超出缓存区大小,防止溢出
if (total > sizeof(buffer))
{
Serial.println("Payload too large");
expected_total = 0; // 重置,放弃此次消息
return;
}
}
// 防止超出缓存区边界,避免溢出
if (index + len > sizeof(buffer))
{
Serial.println("Payload overflow");
expected_total = 0; // 重置状态
return;
}
// 将当前分片数据复制到缓存区对应位置
memcpy(buffer + index, payload, len);
// 判断是否已经接收完所有分片index + len == total
if ((index + len) == expected_total)
{
// 调用原业务处理函数,传入完整拼接的消息数据和长度
mqtt_receiveCallback(topic, buffer, expected_total);
// 清除状态,准备接收下一条消息
expected_total = 0;
}
}
/** /**
* @description: mqtt订阅主题 * @description: mqtt订阅主题
* @param {char*} topic msg/macadd * @param {char*} topic msg/macadd
@ -110,11 +166,6 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length)
fc.playText(todo, volume); // 播放声音 fc.playText(todo, volume); // 播放声音
} }
else if (key == "questAss")
{ // 飞行航点任务 questAss
String todo = value; // 转换值
writeRoute(todo); // 写入航点
}
else if (key == "setQuestState") else if (key == "setQuestState")
{ {
// 设置飞机任务状态 // 设置飞机任务状态
@ -127,7 +178,7 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length)
uint8_t state = obj["state"]; // 标记飞机状态 0 or 1 uint8_t state = obj["state"]; // 标记飞机状态 0 or 1
// 标记飞机状态 // 标记飞机状态
topicPubMsg[10] = fc.setNBit(topicPubMsg[10], n, state); topicPubMsg[10] = fc.setNBit(topicPubMsg[10], n, state);
if (n = 5 && state == 1) // 执行任务 ps:切自动 if (n == 5 && state == 1) // 执行任务 ps:切自动
{ {
funTicker.once(3, []() funTicker.once(3, []()
{ {
@ -194,7 +245,7 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length)
} }
else else
{ {
fc.sendSetPositionTargetGlobalInt(lat, lon, alt); // 发送纬度和高度 fc.sendSetPositionTargetGlobalInt(lat, lon, alt); // 发送度和高度
} }
} }
else if (key == "autoMode") // 自动auto模式 else if (key == "autoMode") // 自动auto模式
@ -889,10 +940,7 @@ void mavlink_receiveCallback(uint8_t c)
mavlink_mission_request_t mission_request; // 解构的数据放到这个对象 mavlink_mission_request_t mission_request; // 解构的数据放到这个对象
mavlink_msg_mission_request_decode(&msg, &mission_request); // 解构msg数据 mavlink_msg_mission_request_decode(&msg, &mission_request); // 解构msg数据
// 日志 // 日志
fc.logln((char *)"MsgID:"); addLogMessage("MsgID:" + String(msg.msgid) + ",No:" + String(mission_request.seq)); // 终端 打印日志
fc.logln(msg.msgid);
fc.logln((char *)"No:");
fc.logln(mission_request.seq);
// 飞控 反馈当前要写入航点的序号 // 飞控 反馈当前要写入航点的序号
fc.writeSeq = mission_request.seq; fc.writeSeq = mission_request.seq;
} }
@ -903,10 +951,7 @@ void mavlink_receiveCallback(uint8_t c)
mavlink_mission_ack_t mission_ark; // 解构的数据放到这个对象 mavlink_mission_ack_t mission_ark; // 解构的数据放到这个对象
mavlink_msg_mission_ack_decode(&msg, &mission_ark); // 解构msg数据 mavlink_msg_mission_ack_decode(&msg, &mission_ark); // 解构msg数据
/*日志*/ /*日志*/
fc.logln((char *)"MsgID:"); addLogMessage("MsgID:" + String(msg.msgid) + ",re:" + String(mission_ark.type)); // 终端 打印日志
fc.logln(msg.msgid);
fc.logln((char *)"re:");
fc.logln(mission_ark.type);
/*记录航点的写入状态 */ /*记录航点的写入状态 */
fc.missionArkType = mission_ark.type; // 0写入成功 非0表示失败 fc.missionArkType = mission_ark.type; // 0写入成功 非0表示失败
/*当有成果反馈之后 初始化下列数据*/ /*当有成果反馈之后 初始化下列数据*/
@ -1011,7 +1056,7 @@ void pubThread()
// 将JSON对象序列化为JSON字符串 // 将JSON对象序列化为JSON字符串
String jsonString; String jsonString;
serializeJson(doc, jsonString); serializeJson(doc, jsonString);
fc.pubMQTTmsg("planeState", jsonString); fc.pubMQTTmsg("planeState", jsonString, 1);
} }
// 添加日志 到日志队列 // 添加日志 到日志队列
void addLogMessage(const String &msg) void addLogMessage(const String &msg)

View File

@ -19,6 +19,7 @@ enum FlightMode
LAND = 9, // 降落模式 LAND = 9, // 降落模式
POSHOLD = 16, // 位置保持模式 POSHOLD = 16, // 位置保持模式
}; };
extern void async_mqtt_receiveCallback(char *topic, char *payload, AsyncMqttClientMessageProperties properties, size_t len, size_t index, size_t total);
extern void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length); extern void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length);
extern void pubThread(); extern void pubThread();
extern void addLogMessage(const String &msg); extern void addLogMessage(const String &msg);

View File

@ -99,7 +99,7 @@ void setup()
{ {
WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0); // 关闭低电压检测,避免无限重启 WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0); // 关闭低电压检测,避免无限重启
// 启用Esp32双核第二个核心 // 启用Esp32双核第二个核心
xTaskCreatePinnedToCore(Task1, "Task1", 10000, NULL, 1, NULL, 0); // 最后一个参数至关重要,决定这个任务创建在哪个核上.PRO_CPU 为 0, APP_CPU 为 1,或者 tskNO_AFFINITY 允许任务在两者上运行. xTaskCreatePinnedToCore(Task1, "Task1", 10000, NULL, 0, NULL, 0); // 最后一个参数至关重要,决定这个任务创建在哪个核上.PRO_CPU 为 0, APP_CPU 为 1,或者 tskNO_AFFINITY 允许任务在两者上运行.
// 调试串口 // 调试串口
Serial.begin(57600); Serial.begin(57600);
@ -120,7 +120,7 @@ void setup()
button_down.attachLongPressStart(downbtn_pressstart); button_down.attachLongPressStart(downbtn_pressstart);
button_down.attachLongPressStop(downbtn_pressend); button_down.attachLongPressStop(downbtn_pressend);
button_checktop.setPressTicks(10); // 10毫秒就产生按下事件用于顶部按钮检测 button_checktop.setPressMs(10); // 10毫秒就产生按下事件用于顶部按钮检测 改为button_checktop.setPressMs(10); button_checktop.setPressTicks(10);
button_checktop.attachLongPressStart(ctbtn_pressstart); // 按下马上产生事件, button_checktop.attachLongPressStart(ctbtn_pressstart); // 按下马上产生事件,
button_checktop.attachLongPressStop(ctbtn_pressend); // 抬起 button_checktop.attachLongPressStop(ctbtn_pressend); // 抬起
@ -148,15 +148,7 @@ void setup()
/*初始化*/ /*初始化*/
Serial1.begin(115200, SERIAL_8N1, SERIAL_REPORT_RX, SERIAL_REPORT_TX); // 声音模块引串口脚映射 Serial1.begin(115200, SERIAL_8N1, SERIAL_REPORT_RX, SERIAL_REPORT_TX); // 声音模块引串口脚映射
fc.playText("开始启动"); fc.playText("开始启动");
fc.connectWifi(); // 连接wifi
// fc.playText("正在连接服务器");
// fc.connectMqtt("cmd"); // 连接mqtt
fc.mqttClient->setCallback(mqtt_receiveCallback); // 设置订阅成功 回调
fc.mav_request_data(); // 指定飞控串口返回的数据类别(飞控启动之后发送才有意义)
/*异步线程在核心0上回调*/
tksendinfo.attach(1, sendinfo); // 发送状态
pubTicker.attach(1, pubThread); // 定时 发布主题
/////////////////////////////////MQTT_语音_MAVLINK 部分结束 /////////////////////////////////MQTT_语音_MAVLINK 部分结束
// if (motocontrol.getstatus()==MS_Stop) // if (motocontrol.getstatus()==MS_Stop)
@ -416,19 +408,46 @@ void set_locked(bool locked)
// 在核心1上执行重要的延迟低的 // 在核心1上执行重要的延迟低的
void loop() void loop()
{ {
_tm_core1 = millis(); unsigned long _tm_core1 = millis();
// sercomm.getcommand(); // 得到控制命令 unsigned long _tm_segment = _tm_core1;
button_checktop.tick(); // 按钮
button_down.tick(); // 按钮
button_up.tick(); // 按钮
button_test.tick();
motocontrol.setweight(pullweight); // 告诉电机拉的重量
motocontrol.update(); // 电机控制
showledidel(); // 显示LED灯光 // 按钮检测
checkstatus(); // 检测状态,执行一些和状态有关的功能 button_checktop.tick();
// showinfo(); // 显示一些调试用信息- button_down.tick();
// 到顶后延迟关闭动力电和舵机 button_up.tick();
button_test.tick();
unsigned long _elapsed = millis() - _tm_segment;
if (_elapsed > 2)
// addLogMessage("core1 timeout: buttons.tick() " + String(_elapsed));
_tm_segment = millis();
// 设置电机拉力
motocontrol.setweight(pullweight);
motocontrol.update();
_elapsed = millis() - _tm_segment;
if (_elapsed > 2)
// addLogMessage("core1 timeout: motocontrol " + String(_elapsed));
_tm_segment = millis();
// 显示LED灯光
showledidel();
_elapsed = millis() - _tm_segment;
if (_elapsed > 2)
// addLogMessage("core1 timeout: showledidel() " + String(_elapsed));
_tm_segment = millis();
// 检查状态
checkstatus();
_elapsed = millis() - _tm_segment;
if (_elapsed > 2)
// addLogMessage("core1 timeout: checkstatus() " + String(_elapsed));
_tm_segment = millis();
// 处理到顶延时逻辑
if (_bengstop) if (_bengstop)
{ {
if ((initstatus == IS_OK) && (pullweight > TM_INSTORE_DELAY_WEIGHT)) if ((initstatus == IS_OK) && (pullweight > TM_INSTORE_DELAY_WEIGHT))
@ -448,16 +467,35 @@ void loop()
} }
} }
} }
check_tare(); // 检查看是否需要校准称重
checkinited(); // 检测执行初始化工作 _elapsed = millis() - _tm_segment;
delay(1); if (_elapsed > 2)
_looptm_core1 = millis() - _tm_core1; // addLogMessage("core1 timeout: _bengstop logic " + String(_elapsed));
// 如果循环时间超过1000ms,则打印错误日志 _tm_segment = millis();
// 校准检测
check_tare();
_elapsed = millis() - _tm_segment;
if (_elapsed > 2)
// addLogMessage("core1 timeout: check_tare() " + String(_elapsed));
_tm_segment = millis();
// 初始化检测
checkinited();
_elapsed = millis() - _tm_segment;
if (_elapsed > 2)
/// addLogMessage("core1 timeout: checkinited() " + String(_elapsed));
_tm_segment = millis();
vTaskDelay(1);
unsigned long _looptm_core1 = millis() - _tm_core1;
if (_looptm_core1 > 10) if (_looptm_core1 > 10)
{ {
// ESP_LOGE(MOUDLENAME, "main loop time out %d ms", _looptm_core1); // addLogMessage("core1 timeout: loop total " + String(_looptm_core1));
addLogMessage("core1 timeout: " + String(_looptm_core1));
} }
} }
// 在核心0上执行耗时长的低优先级的 // 在核心0上执行耗时长的低优先级的
@ -468,6 +506,18 @@ void Task1(void *pvParameters)
scale.set_scale(WEIGHT_SCALE); // 这是缩放值根据砝码实测516.f scale.set_scale(WEIGHT_SCALE); // 这是缩放值根据砝码实测516.f
scale.tare(); // 重置为0 scale.tare(); // 重置为0
// 连接wifi
fc.connectWifi();
// 指定飞控串口返回的数据类别(飞控启动之后发送才有意义)
fc.mav_request_data();
/*异步线程在核心0上回调*/
tksendinfo.attach(1, sendinfo); // 发送状态
pubTicker.attach(1, pubThread); // 定时 发布主题
// mqtt初始化
fc.mqttClient->onMessage(async_mqtt_receiveCallback); // 设置mqtt的订阅回调函数
// 在这里可以添加一些代码这样的话这个任务执行时会先执行一次这里的内容当然后面进入while循环之后不会再执行这部分了 // 在这里可以添加一些代码这样的话这个任务执行时会先执行一次这里的内容当然后面进入while循环之后不会再执行这部分了
while (1) while (1)
{ {
@ -483,14 +533,53 @@ void Task1(void *pvParameters)
/*从飞控拿数据*/ /*从飞控拿数据*/
fc.comm_receive(mavlink_receiveCallback); fc.comm_receive(mavlink_receiveCallback);
// vTaskDelay(1);
if (fc.checkWiFiStatus()) // 保持wifi mqtt的链接
fc.mqttLoop("cmd"); // 保持mqtt心跳,如果Mqtt没有连接会自动连接 if (fc.checkWiFiStatus() && !fc.mqttClient->connected())
{
// 用 static 防止每次 loop 都重新设置 onConnect 和重复订阅
static bool mqttTopicSet = false;
// 控制 MQTT 重连尝试的时间间隔(避免频繁重连)
static unsigned long lastMqttAttempt = 0;
const unsigned long mqttRetryInterval = 5000; // 每隔 5 秒尝试一次
unsigned long now = millis(); // 获取当前时间
// 如果距离上次尝试连接的时间超过了设定间隔
if (now - lastMqttAttempt > mqttRetryInterval)
{
lastMqttAttempt = now; // 记录本次尝试连接的时间
// 尝试连接 MQTT 服务器(只在未连接状态下尝试)
fc.mqttClient->connect();
// mqtt链接成功 回调
fc.mqttClient->onConnect(
[](bool sessionPresent)
{
/*链接成功后 初始化*/
if (!mqttTopicSet)
{
fc.mqttClient->setClientId((fc.macAdd).c_str()); // 设置唯一 client ID
fc.subscribeTopic(fc.mqttTopic, 1); // 订阅主题 ps:subscribeTopic内会拼接主题 cmd/macAdd 之所以写在这里因为需要先链接wifi之后才能获取到macAdd
mqttTopicSet = true; // 设置标志,避免重复绑定
}
/*链接成功后 执行*/
fc.playText("指令服务器已链接。");
});
// mqtt链接失败 回调
fc.mqttClient->onDisconnect(
[](AsyncMqttClientDisconnectReason reason)
{
fc.playText("指令服务器已断开,尝试重新连接。");
});
}
}
vTaskDelay(10); vTaskDelay(10);
_looptm_core0 = millis() - _tm_core0; _looptm_core0 = millis() - _tm_core0;
/*如果循环时间超过100ms,则打印错误日志*/ /*如果循环时间超过100ms,则打印错误日志*/
if (_looptm_core0 > 50) if (_looptm_core0 > 200)
{ {
addLogMessage("core0 timeout: " + String(_looptm_core0)); addLogMessage("core0 timeout: " + String(_looptm_core0));
} }
@ -742,7 +831,7 @@ void btn_presssatonce()
addLogMessage("UP_presssatonce"); addLogMessage("UP_presssatonce");
led_show(255, 255, 255); // 高亮一下 led_show(255, 255, 255); // 高亮一下
fc.playText("发送对频信息"); fc.playText("发送对频信息");
fc.pubMQTTmsg(topicHandle[0], fc.getMacAdd()); fc.pubMQTTmsg(topicHandle[0], fc.getMacAdd(), 0);
} }
// 收线按钮-长按 // 收线按钮-长按
void upbtn_pressstart() void upbtn_pressstart()

View File

@ -6,7 +6,8 @@
#define ROPE_MAXLENGTH 700 // 最多能放700cm---实际绳子应该比这个长750之类的 #define ROPE_MAXLENGTH 700 // 最多能放700cm---实际绳子应该比这个长750之类的
// #define WHEEL_DIAMETER 3.8 // 轮子直径cm // #define WHEEL_DIAMETER 3.8 // 轮子直径cm
#define WHEEL_DIAMETER 2.3 // 轮子直径cm 小轮子直径 // #define WHEEL_DIAMETER 2.3 // 轮子直径cm 小轮子直径实际直径2cm
#define WHEEL_DIAMETER 2 // 轮子直径cm 小轮子直径(实际直径1.7cm)
#define WHEEL_PERIMETER (WHEEL_DIAMETER * 3.1416) // 轮子周长 #define WHEEL_PERIMETER (WHEEL_DIAMETER * 3.1416) // 轮子周长
#define ROPE_MAXCOUNT (ROPE_MAXLENGTH / WHEEL_PERIMETER) // 最大圈数 #define ROPE_MAXCOUNT (ROPE_MAXLENGTH / WHEEL_PERIMETER) // 最大圈数