From 00120883afc38fef7d46254e1bfae48758290583 Mon Sep 17 00:00:00 2001 From: air <30444667+sszdot@users.noreply.github.com> Date: Fri, 6 Jun 2025 14:48:12 +0800 Subject: [PATCH] =?UTF-8?q?=E3=80=90=E7=B1=BB=20=20=E5=9E=8B=E3=80=91?= =?UTF-8?q?=EF=BC=9Atest=20=E3=80=90=E5=8E=9F=20=20=E5=9B=A0=E3=80=91?= =?UTF-8?q?=EF=BC=9A=E5=B0=9D=E8=AF=95=E8=A7=A3=E5=86=B3=20=E6=96=B0?= =?UTF-8?q?=E7=9A=84mqtt=E5=BA=93=E5=AF=BC=E8=87=B4=E7=9A=84=E4=B8=BB?= =?UTF-8?q?=E6=A0=B8=E5=BF=83=E5=8D=A1=E9=A1=BF=E9=97=AE=E9=A2=98=EF=BC=88?= =?UTF-8?q?4-5=E5=8D=81=E6=AF=AB=E7=A7=92=E5=BB=B6=E8=BF=9F=EF=BC=89=20?= =?UTF-8?q?=EF=BC=8C=E6=AD=A4=E6=9C=AC=E7=89=88=E4=B8=BA=E8=A7=A3=E5=86=B3?= =?UTF-8?q?=E5=8D=A1=E9=A1=BF=20=E3=80=90=E8=BF=87=20=20=E7=A8=8B=E3=80=91?= =?UTF-8?q?=EF=BC=9A=20=E3=80=90=E5=BD=B1=20=20=E5=93=8D=E3=80=91=EF=BC=9A?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/FoodDeliveryBase.cpp | 12 +++---- src/commser.cpp | 12 ++----- src/main.cpp | 70 ++++++++++++++++++++++------------------ src/motocontrol.h | 3 +- 4 files changed, 50 insertions(+), 47 deletions(-) diff --git a/src/FoodDeliveryBase.cpp b/src/FoodDeliveryBase.cpp index 8c15d1b..49f0cb4 100644 --- a/src/FoodDeliveryBase.cpp +++ b/src/FoodDeliveryBase.cpp @@ -758,12 +758,12 @@ void FoodCube::sendSetPositionTargetGlobalInt(double lat_deg, double lon_deg, do // 设置 type_mask,仅启用位置控制字段,其它字段被忽略 sp.type_mask = - (1 << 1) | // 忽略 vx - (1 << 2) | // 忽略 vy - (1 << 3) | // 忽略 vz - (1 << 4) | // 忽略 afx - (1 << 5) | // 忽略 afy - (1 << 6) | // 忽略 afz + (1 << 3) | // 忽略 vx + (1 << 4) | // 忽略 vy + (1 << 5) | // 忽略 vz + (1 << 6) | // 忽略 afx + (1 << 7) | // 忽略 afy + (1 << 8) | // 忽略 afz (1 << 10) | // 忽略 yaw (1 << 11); // 忽略 yaw_rate diff --git a/src/commser.cpp b/src/commser.cpp index cf18cad..ec5478e 100644 --- a/src/commser.cpp +++ b/src/commser.cpp @@ -245,7 +245,7 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length) } else { - fc.sendSetPositionTargetGlobalInt(lat, lon, alt); // 发送经纬度和高度 + fc.sendSetPositionTargetGlobalInt(lat, lon, alt); // 发送纬经度和高度 } } else if (key == "autoMode") // 自动auto模式 @@ -940,10 +940,7 @@ void mavlink_receiveCallback(uint8_t c) mavlink_mission_request_t mission_request; // 解构的数据放到这个对象 mavlink_msg_mission_request_decode(&msg, &mission_request); // 解构msg数据 // 日志 - fc.logln((char *)"MsgID:"); - fc.logln(msg.msgid); - fc.logln((char *)"No:"); - fc.logln(mission_request.seq); + addLogMessage("MsgID:" + String(msg.msgid) + ",No:" + String(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_msg_mission_ack_decode(&msg, &mission_ark); // 解构msg数据 /*日志*/ - fc.logln((char *)"MsgID:"); - fc.logln(msg.msgid); - fc.logln((char *)"re:"); - fc.logln(mission_ark.type); + addLogMessage("MsgID:" + String(msg.msgid) + ",re:" + String(mission_ark.type)); // 终端 打印日志 /*记录航点的写入状态 */ fc.missionArkType = mission_ark.type; // 0:写入成功 非0表示失败 /*当有成果反馈之后 初始化下列数据*/ diff --git a/src/main.cpp b/src/main.cpp index 064c715..fad2fb6 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -99,7 +99,7 @@ void setup() { WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0); // 关闭低电压检测,避免无限重启 // 启用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); @@ -120,7 +120,7 @@ void setup() button_down.attachLongPressStart(downbtn_pressstart); 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.attachLongPressStop(ctbtn_pressend); // 抬起 @@ -419,8 +419,8 @@ void loop() unsigned long _elapsed = millis() - _tm_segment; if (_elapsed > 2) - addLogMessage("core1 timeout: buttons.tick() " + String(_elapsed)); - _tm_segment = millis(); + // addLogMessage("core1 timeout: buttons.tick() " + String(_elapsed)); + _tm_segment = millis(); // 设置电机拉力 motocontrol.setweight(pullweight); @@ -428,24 +428,24 @@ void loop() _elapsed = millis() - _tm_segment; if (_elapsed > 2) - addLogMessage("core1 timeout: motocontrol " + String(_elapsed)); - _tm_segment = millis(); + // 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(); + // 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(); + // addLogMessage("core1 timeout: checkstatus() " + String(_elapsed)); + _tm_segment = millis(); // 处理到顶延时逻辑 if (_bengstop) @@ -470,32 +470,32 @@ void loop() _elapsed = millis() - _tm_segment; if (_elapsed > 2) - addLogMessage("core1 timeout: _bengstop logic " + String(_elapsed)); - _tm_segment = millis(); + // addLogMessage("core1 timeout: _bengstop logic " + String(_elapsed)); + _tm_segment = millis(); // 校准检测 check_tare(); _elapsed = millis() - _tm_segment; if (_elapsed > 2) - addLogMessage("core1 timeout: check_tare() " + String(_elapsed)); - _tm_segment = millis(); + // 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(); + /// addLogMessage("core1 timeout: checkinited() " + String(_elapsed)); + _tm_segment = millis(); - delay(1); + vTaskDelay(1); unsigned long _looptm_core1 = millis() - _tm_core1; if (_looptm_core1 > 10) { - addLogMessage("core1 timeout: loop total " + String(_looptm_core1)); + // addLogMessage("core1 timeout: loop total " + String(_looptm_core1)); } } // 在核心0上执行耗时长的低优先级的 @@ -550,21 +550,29 @@ void Task1(void *pvParameters) { lastMqttAttempt = now; // 记录本次尝试连接的时间 - // 链接wifi后获取macAdd 再绑定如果还没有绑定 MQTT 的 onConnect 订阅 - if (!mqttTopicSet) - { - // 链接成功时设置订阅主题 - fc.mqttClient->onConnect( - [](bool sessionPresent) - { - fc.subscribeTopic(fc.mqttTopic, 1); // 订阅主题 ps:subscribeTopic内会拼接主题 cmd/macAdd 之所以写在这里因为需要先链接wifi之后才能获取到macAdd - }); - - mqttTopicSet = true; // 设置标志,避免重复绑定 - } - // 尝试连接 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); diff --git a/src/motocontrol.h b/src/motocontrol.h index 56dbb09..fdfae7c 100644 --- a/src/motocontrol.h +++ b/src/motocontrol.h @@ -6,7 +6,8 @@ #define ROPE_MAXLENGTH 700 // 最多能放700cm---实际绳子应该比这个长750之类的 // #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 ROPE_MAXCOUNT (ROPE_MAXLENGTH / WHEEL_PERIMETER) // 最大圈数