【类 型】:test
【原 因】:尝试解决 新的mqtt库导致的主核心卡顿问题(4-5十毫秒延迟) ,此本版为解决卡顿 【过 程】: 【影 响】:
This commit is contained in:
parent
3445924e10
commit
00120883af
@ -758,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
|
||||||
|
|
||||||
|
@ -245,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模式
|
||||||
@ -940,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;
|
||||||
}
|
}
|
||||||
@ -954,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表示失败
|
||||||
/*当有成果反馈之后 初始化下列数据*/
|
/*当有成果反馈之后 初始化下列数据*/
|
||||||
|
48
src/main.cpp
48
src/main.cpp
@ -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);
|
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); // 抬起
|
||||||
|
|
||||||
@ -419,7 +419,7 @@ void loop()
|
|||||||
|
|
||||||
unsigned long _elapsed = millis() - _tm_segment;
|
unsigned long _elapsed = millis() - _tm_segment;
|
||||||
if (_elapsed > 2)
|
if (_elapsed > 2)
|
||||||
addLogMessage("core1 timeout: buttons.tick() " + String(_elapsed));
|
// addLogMessage("core1 timeout: buttons.tick() " + String(_elapsed));
|
||||||
_tm_segment = millis();
|
_tm_segment = millis();
|
||||||
|
|
||||||
// 设置电机拉力
|
// 设置电机拉力
|
||||||
@ -428,7 +428,7 @@ void loop()
|
|||||||
|
|
||||||
_elapsed = millis() - _tm_segment;
|
_elapsed = millis() - _tm_segment;
|
||||||
if (_elapsed > 2)
|
if (_elapsed > 2)
|
||||||
addLogMessage("core1 timeout: motocontrol " + String(_elapsed));
|
// addLogMessage("core1 timeout: motocontrol " + String(_elapsed));
|
||||||
_tm_segment = millis();
|
_tm_segment = millis();
|
||||||
|
|
||||||
// 显示LED灯光
|
// 显示LED灯光
|
||||||
@ -436,7 +436,7 @@ void loop()
|
|||||||
|
|
||||||
_elapsed = millis() - _tm_segment;
|
_elapsed = millis() - _tm_segment;
|
||||||
if (_elapsed > 2)
|
if (_elapsed > 2)
|
||||||
addLogMessage("core1 timeout: showledidel() " + String(_elapsed));
|
// addLogMessage("core1 timeout: showledidel() " + String(_elapsed));
|
||||||
_tm_segment = millis();
|
_tm_segment = millis();
|
||||||
|
|
||||||
// 检查状态
|
// 检查状态
|
||||||
@ -444,7 +444,7 @@ void loop()
|
|||||||
|
|
||||||
_elapsed = millis() - _tm_segment;
|
_elapsed = millis() - _tm_segment;
|
||||||
if (_elapsed > 2)
|
if (_elapsed > 2)
|
||||||
addLogMessage("core1 timeout: checkstatus() " + String(_elapsed));
|
// addLogMessage("core1 timeout: checkstatus() " + String(_elapsed));
|
||||||
_tm_segment = millis();
|
_tm_segment = millis();
|
||||||
|
|
||||||
// 处理到顶延时逻辑
|
// 处理到顶延时逻辑
|
||||||
@ -470,7 +470,7 @@ void loop()
|
|||||||
|
|
||||||
_elapsed = millis() - _tm_segment;
|
_elapsed = millis() - _tm_segment;
|
||||||
if (_elapsed > 2)
|
if (_elapsed > 2)
|
||||||
addLogMessage("core1 timeout: _bengstop logic " + String(_elapsed));
|
// addLogMessage("core1 timeout: _bengstop logic " + String(_elapsed));
|
||||||
_tm_segment = millis();
|
_tm_segment = millis();
|
||||||
|
|
||||||
// 校准检测
|
// 校准检测
|
||||||
@ -478,7 +478,7 @@ void loop()
|
|||||||
|
|
||||||
_elapsed = millis() - _tm_segment;
|
_elapsed = millis() - _tm_segment;
|
||||||
if (_elapsed > 2)
|
if (_elapsed > 2)
|
||||||
addLogMessage("core1 timeout: check_tare() " + String(_elapsed));
|
// addLogMessage("core1 timeout: check_tare() " + String(_elapsed));
|
||||||
_tm_segment = millis();
|
_tm_segment = millis();
|
||||||
|
|
||||||
// 初始化检测
|
// 初始化检测
|
||||||
@ -486,16 +486,16 @@ void loop()
|
|||||||
|
|
||||||
_elapsed = millis() - _tm_segment;
|
_elapsed = millis() - _tm_segment;
|
||||||
if (_elapsed > 2)
|
if (_elapsed > 2)
|
||||||
addLogMessage("core1 timeout: checkinited() " + String(_elapsed));
|
/// addLogMessage("core1 timeout: checkinited() " + String(_elapsed));
|
||||||
_tm_segment = millis();
|
_tm_segment = millis();
|
||||||
|
|
||||||
delay(1);
|
vTaskDelay(1);
|
||||||
|
|
||||||
unsigned long _looptm_core1 = millis() - _tm_core1;
|
unsigned long _looptm_core1 = millis() - _tm_core1;
|
||||||
|
|
||||||
if (_looptm_core1 > 10)
|
if (_looptm_core1 > 10)
|
||||||
{
|
{
|
||||||
addLogMessage("core1 timeout: loop total " + String(_looptm_core1));
|
// addLogMessage("core1 timeout: loop total " + String(_looptm_core1));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// 在核心0上执行耗时长的低优先级的
|
// 在核心0上执行耗时长的低优先级的
|
||||||
@ -550,21 +550,29 @@ void Task1(void *pvParameters)
|
|||||||
{
|
{
|
||||||
lastMqttAttempt = now; // 记录本次尝试连接的时间
|
lastMqttAttempt = now; // 记录本次尝试连接的时间
|
||||||
|
|
||||||
// 链接wifi后获取macAdd 再绑定如果还没有绑定 MQTT 的 onConnect 订阅
|
// 尝试连接 MQTT 服务器(只在未连接状态下尝试)
|
||||||
if (!mqttTopicSet)
|
fc.mqttClient->connect();
|
||||||
{
|
|
||||||
// 链接成功时设置订阅主题
|
// mqtt链接成功 回调
|
||||||
fc.mqttClient->onConnect(
|
fc.mqttClient->onConnect(
|
||||||
[](bool sessionPresent)
|
[](bool sessionPresent)
|
||||||
{
|
{
|
||||||
|
/*链接成功后 初始化*/
|
||||||
|
if (!mqttTopicSet)
|
||||||
|
{
|
||||||
|
fc.mqttClient->setClientId((fc.macAdd).c_str()); // 设置唯一 client ID
|
||||||
fc.subscribeTopic(fc.mqttTopic, 1); // 订阅主题 ps:subscribeTopic内会拼接主题 cmd/macAdd 之所以写在这里因为需要先链接wifi之后才能获取到macAdd
|
fc.subscribeTopic(fc.mqttTopic, 1); // 订阅主题 ps:subscribeTopic内会拼接主题 cmd/macAdd 之所以写在这里因为需要先链接wifi之后才能获取到macAdd
|
||||||
});
|
|
||||||
|
|
||||||
mqttTopicSet = true; // 设置标志,避免重复绑定
|
mqttTopicSet = true; // 设置标志,避免重复绑定
|
||||||
}
|
}
|
||||||
|
/*链接成功后 执行*/
|
||||||
// 尝试连接 MQTT 服务器(只在未连接状态下尝试)
|
fc.playText("指令服务器已链接。");
|
||||||
fc.mqttClient->connect();
|
});
|
||||||
|
// mqtt链接失败 回调
|
||||||
|
fc.mqttClient->onDisconnect(
|
||||||
|
[](AsyncMqttClientDisconnectReason reason)
|
||||||
|
{
|
||||||
|
fc.playText("指令服务器已断开,尝试重新连接。");
|
||||||
|
});
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
vTaskDelay(10);
|
vTaskDelay(10);
|
||||||
|
@ -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) // 最大圈数
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user