1.空钩加锁完全不延时也可能顶部按键没可靠按下去,加一点延时 ms

2.Mqtt重连接加入3秒延时
3.mqtt域名改为ip防止dns失败
4.到顶停止只是在上升和未初始化时有效,下放时无效
This commit is contained in:
pxzleo 2023-07-14 17:50:20 +08:00
parent 3adea2fc5e
commit e52ca01d9e
4 changed files with 45 additions and 28 deletions

View File

@ -1,5 +1,4 @@
#include "FoodDeliveryBase.h"
/**
* @description:
*/
@ -16,6 +15,7 @@ FoodCube::FoodCube(char* userSsid, char* userPassword, char* userMqttServer, int
udpServerIP = userUdpServerIP; //云台相机ip
udpServerPort = userUdpServerPort; //云台相机端口
wificonnected=false;
_tm_mqttconnect=0;
//初始化飞控通讯串口 波特率
switch (mavlinkSerial) { //初始化指定 串口号
@ -165,24 +165,30 @@ bool FoodCube::checkWiFiStatus()
void FoodCube::connectMqtt(String topicSub[], int topicSubCount) {
if (mqttClient->connected()) return;
/*尝试连接mqtt*/
log("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
for (int i = 0; i < topicSubCount; i++) { //遍历 订阅主题
subscribeTopic(topicSub[i], 1);
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
for (int i = 0; i < topicSubCount; i++) { //遍历 订阅主题
subscribeTopic(topicSub[i], 1);
}
delay(500);
playText("[v1]指令服务器已连接");
} else {
//失败返回状态码
log("MQTT Server Connect Failed. Client State:");
logln(mqttClient->state());
_tm_mqttconnect=millis();
//delay(3000);
}
playText("[v1]指令服务器已连接");
} else {
//失败返回状态码
log("MQTT Server Connect Failed. Client State:");
logln(mqttClient->state());
//delay(3000);
}
}

View File

@ -89,6 +89,10 @@ private:
WiFiUDP udp; //udp信息操作对象
char* udpServerIP; //云台相机ip地址
uint32_t udpServerPort; //云台相机端口
unsigned long _tm_mqttconnect; //mqtt上次连接时间
//摄像头控制 校验代码
const uint16_t crc16_tab[256] = { 0x0, 0x1021, 0x2042, 0x3063, 0x4084, 0x50a5, 0x60c6, 0x70e7,
0x8108, 0x9129, 0xa14a, 0xb16b, 0xc18c, 0xd1ad, 0xe1ce, 0xf1ef,

View File

@ -25,8 +25,9 @@
#define SERIAL_REPORT_RX 18
/////
#define WEIGHT_SCALE 165 // 276 //这是缩放值根据砝码实测516.f
#define TM_INSTORE_DELAY 200 //200 // 入仓动力延时关闭时间 ms
#define TM_INSTORE_WEIGHT_DELAY 200 //200 // 入仓动力延时关闭时间 ms
#define TM_INSTORE_DELAY_WEIGHT 200 // 入仓动力延时关闭时间生效的重量(g),免得空钩也延时关闭导致线拉紧 ms
#define TM_INSTORE_NOWEIGHT_DELAY 50 // 空钩完全不延时也可能顶部按键按不下去,加一点延时 ms

View File

@ -95,7 +95,7 @@ const uint16_t MAV_CMD_FC_HOOK_RECOVERY=43; //飞控发的---收线
//char* password = "Ttaj@#*.com"; //wifi密码
char* ssid = (char*)"fxmf_sc01"; //wifi帐号
char* password = (char*)"12345678"; //wifi密码
char* mqttServer = (char*)"szdot.top"; //mqtt地址
char* mqttServer = (char*)"114.115.137.239";//"szdot.top"; //mqtt地址
int mqttPort = 1883; //mqtt端口
char* mqttName = (char*)"admin"; //mqtt帐号
char* mqttPassword = (char*)"123456"; //mqtt密码
@ -368,7 +368,7 @@ void loop()
button_up.tick(); // 按钮
button_test.tick();
motocontrol.setweight(pullweight); // 告诉电机拉的重量
motocontrol.update(); // 电机控制
motocontrol.update(); // 电机控制
showledidel(); // 显示LED灯光
@ -378,7 +378,7 @@ void loop()
{
if ((initstatus==IS_OK)&&(pullweight>TM_INSTORE_DELAY_WEIGHT) )
{
if ((millis() - _tm_bengstop) > TM_INSTORE_DELAY)
if ((millis() - _tm_bengstop) > TM_INSTORE_WEIGHT_DELAY)
{
_bengstop = false;
motocontrol.setlocked(true);
@ -386,8 +386,11 @@ void loop()
}
else
{
_bengstop = false;
motocontrol.setlocked(true);
if ((millis() - _tm_bengstop) > TM_INSTORE_NOWEIGHT_DELAY)
{
_bengstop = false;
motocontrol.setlocked(true);
}
}
}
@ -460,7 +463,7 @@ void showledidel()
// 超重--红色
if (motocontrol.getcontrolstatus().is_overweight)
{
led_show(255, 0, 0); // 红
led_show(255, 0, 255); // 紫
return;
}
switch (motocontrol.gethooktatus())
@ -553,9 +556,12 @@ void showledidel()
void ctbtn_pressstart()
{
Serial.println("ctbtn_pressstart");
_tm_bengstop = millis();
_bengstop = true;
//只在上升时停止
if ((motocontrol.gethooktatus()== HS_UnInit)||(motocontrol.gethooktatus()== HS_Up)||(motocontrol.gethooktatus()== HS_InStore))
{
_tm_bengstop = millis();
_bengstop = true;
}
}
// 顶部按钮,抬起
void ctbtn_pressend()