diff --git a/src/main.cpp b/src/main.cpp index 3d90c0f..ce73a21 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -49,6 +49,7 @@ void ctbtn_pressend(); void ctbtn_pressstart(); void testbtn_click(); +void btn_presssatonce(); int get_pullweight(); void Task1(void *pvParameters); @@ -56,9 +57,14 @@ void led_show(CRGB ledcolor); // void Task1code( void *pvParameters ); void showledidel(); int pullweight = 0; +int8_t btn_pressatonce=0; //是否同时按下 unsigned long _tm_bengstop; bool _bengstop = false; bool _needweightalign = false; + +bool curr_armed=false; +uint8_t curr_mode=0; + // 需要做的初始化工作 enum Initstatus { @@ -116,7 +122,7 @@ boolean isPush = false; //记得删除 板子按钮状态 ps:D3引脚下拉微 /*异步线程对象*/ Ticker pubTicker(pubThread,1000); //定时发布主题 线程 Ticker mavTicker(mavThread,10000); //定时 指定飞控mavlink 串口返回的数据类别 防止飞控启动滞后 -Ticker flashTicker(flashThread,50); //单片机主动 按钮主动发布主题 线程 +//Ticker flashTicker(flashThread,50); //单片机主动 按钮主动发布主题 线程 /////////////////////////////////MQTT_语音_MAVLINK 部分结束 void setup() @@ -173,7 +179,9 @@ void setup() /////////////////////////////////MQTT_语音_MAVLINK 部分 /*初始化*/ Serial1.begin(115200, SERIAL_8N1, SERIAL_REPORT_RX, SERIAL_REPORT_TX); //声音模块引串口脚映射 + // fc.playText("正在连接服WIFI"); fc.connectWifi(); //连接wifi + // fc.playText("正在连接服务器"); fc.connectMqtt(topicSub, topicSubCount); //连接mqtt fc.mqttClient->setCallback(mqtt_receiveCallback); //设置订阅成功 回调 fc.mav_request_data(); //指定飞控串口返回的数据类别(飞控启动之后发送才有意义) @@ -181,7 +189,7 @@ void setup() /*异步线程*/ pubTicker.start(); //定时 发布主题 mavTicker.start(); //定时 指定飞控mavlink 串口返回的数据类别 防止飞控启动滞后 - flashTicker.start(); //监听 按flash键时 主动发布对频主题 + //flashTicker.start(); //监听 按flash键时 主动发布对频主题 /////////////////////////////////MQTT_语音_MAVLINK 部分结束 @@ -192,7 +200,7 @@ void setup() // //slowup(); // } - + fc.playText("启动完成"); Serial.println("PullupDevice is ready!"); } void slowup() @@ -321,7 +329,11 @@ void checkinited() // 在核心1上执行,重要的延迟低的 void loop() { - tksendinfo.update(); // 定时发送信息任务 + // tksendinfo.update(); // 定时发送信息任务 + pubTicker.update(); //定时 发布主题 + mavTicker.update(); //定时 指定飞控mavlink 串口返回的数据类别 防止飞控启动滞后 + + sercomm.getcommand(); // 得到控制命令 button_checktop.tick(); // 按钮 button_down.tick(); // 按钮 @@ -496,6 +508,16 @@ void downbtn_dbclick() void downbtn_pressstart() { Serial.println("downbtn_pressstart"); + //两个同时按用于对频 + btn_pressatonce++; + if (btn_pressatonce>2) btn_pressatonce=2; + if (btn_pressatonce==2) + { + btn_presssatonce(); + return; + } + + if (motocontrol.getcontrolstatus().motostatus != MotoStatus::MS_Stop) { motocontrol.stop(); @@ -510,6 +532,9 @@ void downbtn_pressstart() void downbtn_pressend() { Serial.println("downbtn_pressend"); + btn_pressatonce--; + if (btn_pressatonce<0) btn_pressatonce=0; + motocontrol.stop(); } @@ -541,10 +566,27 @@ void upbtn_dbclick() motocontrol.moto_run(MotoStatus::MS_Up); } } +// 两个按钮同时按下 +void btn_presssatonce() +{ + Serial.println("btn_presssatonce"); + led_show(255,255, 255); // 高亮一下 + fc.playText("发送对频信息"); + fc.pubMQTTmsg(topicHandle[0], fc.getMacAdd()); +} // 收线按钮-长按 void upbtn_pressstart() { Serial.println("upbtn_pressstart"); + //两个同时按用于对频 + btn_pressatonce++; + if (btn_pressatonce>2) btn_pressatonce=2; + if (btn_pressatonce==2) + { + btn_presssatonce(); + return; + } + if (motocontrol.getcontrolstatus().motostatus != MotoStatus::MS_Stop) { motocontrol.stop(); @@ -559,6 +601,9 @@ void upbtn_pressstart() void upbtn_pressend() { Serial.println("upbtn_pressend"); + btn_pressatonce--; + if (btn_pressatonce<0) btn_pressatonce=0; + motocontrol.stop(); } @@ -789,8 +834,14 @@ void mavlink_receiveCallback(mavlink_message_t* pMsg, mavlink_status_t* pStatus, topicPubMsg[0] = buf; //心跳主题 //从心跳里判断 飞机是否解锁 解锁改变飞机状态 if (heartbeat.base_mode & 128) { //从心跳里面 判断已经解锁 + if (!curr_armed) + fc.playText("已解锁"); + curr_armed=true; topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 4, 1); //设置飞机状态为已解锁状态 1xxxx 第四位为1 代表已解锁 - } else { //心跳里面 判断没有解锁 + } else { + if (curr_armed) + fc.playText("已加锁"); + curr_armed=false; //心跳里面 判断没有解锁 topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 4, 0); //设置飞机状态为已解锁状态 0xxxx 第四位为0 代表未解锁 if ((uint8_t)topicPubMsg[10].toInt() & 4) { //如果已经写入了航点 topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 2, 1); //设置为航点写入成功状态 @@ -799,53 +850,59 @@ void mavlink_receiveCallback(mavlink_message_t* pMsg, mavlink_status_t* pStatus, } } //从心跳里面 判断飞机当前的模式 + if (curr_mode!=heartbeat.custom_mode) + { + curr_mode=heartbeat.custom_mode; + switch (heartbeat.custom_mode) { case 0: { - topicPubMsg[12] = "Stabilize自稳"; + topicPubMsg[12] = "姿态模式"; } break; case 2: { - topicPubMsg[12] = "AltHold定高"; + topicPubMsg[12] = "定高模式"; } break; case 3: { - topicPubMsg[12] = "Auto自动"; + topicPubMsg[12] = "自动模式"; } break; case 4: { - topicPubMsg[12] = "Guided引导"; + topicPubMsg[12] = "引导模式"; } break; case 5: { - topicPubMsg[12] = "Loiter留待"; + topicPubMsg[12] = "悬停模式"; } break; case 6: { - topicPubMsg[12] = "RTL返航"; + topicPubMsg[12] = "返航模式"; } break; case 9: { - topicPubMsg[12] = "Land降落"; + topicPubMsg[12] = "降落模式"; } break; case 16: { - topicPubMsg[12] = "PosHold定点"; + topicPubMsg[12] = "定点模式"; } break; default: { - topicPubMsg[12] = "Unknown未知"; + topicPubMsg[12] = "未知模式"; } break; } + fc.playText(topicPubMsg[12]); + } } break; @@ -1022,6 +1079,7 @@ void pubThread() { } //发送心跳包 fc.pubMQTTmsg(topicPub[0], topicPubMsg[0]); + // printf("pub%s:%s\n",topicPub[0],topicPubMsg[0]); } else { //非心跳包 有更新才向对应主题发布信息 fc.pubMQTTmsg(topicPub[i], topicPubMsg[i]); oldMsg[i] = topicPubMsg[i];