【类 型】:feat

【主	题】:播放声音修改,
              兼容第二版硬件
【描	述】:
	[原因]:需要播放声音测试
                 音量太大
                 新硬件回来
	[过程]:
               增加编译选项对不同的硬件
               声音测试代码
               增加音量调节函数

	[影响]:还未完全测试
【结	束】

# 类型 包含:
# feat:新功能(feature)
# fix:修补bug
# docs:文档(documentation)
# style: 格式(不影响代码运行的变动)
# refactor:重构(即不是新增功能,也不是修改bug的代码变动)
# test:增加测试
# chore:构建过程或辅助工具的变动
This commit is contained in:
xu 2024-05-30 17:33:53 +08:00
parent 8da4ad4693
commit a1bb1bb40f
6 changed files with 108 additions and 51 deletions

17
README.md Normal file
View File

@ -0,0 +1,17 @@
机载控制端esp32程序
主要功能:
控制钩子自动收放
和飞控通讯发送航线,转发飞控控制和状态
控制喇叭
根据mqtt指令直接控制摄像头
物理连接:
wifi连接4G模块
TTL连接飞控
模拟输出连接喇叭
内网udp连接摄像头推流服务器
CAN连接收放控制电机
PWM连接锁定舵机
模拟连接称重传感器
IO连接开关控制
IO连接LED灯控制

View File

@ -12,7 +12,7 @@
platform = espressif32
board = esp32doit-devkit-v1
framework = arduino
build_flags = -DCORE_DEBUG_LEVEL=5
build_flags = -DCORE_DEBUG_LEVEL=4
monitor_speed = 115200
upload-port = COM[14]
lib_deps =

View File

@ -44,6 +44,7 @@ FoodCube::FoodCube(char* userSsid, char* userPassword, char* userMqttServer, int
}
/*初始化 连接mqtt对象 赋予mqttClient指针*/
mqttClient = new PubSubClient(mqttServer, mqttPort, wifiClient);
SetplayvolMax();
}
/**
* @description:
@ -107,9 +108,9 @@ IPAddress secondaryDNS(8, 8, 4, 4); //optional
void FoodCube::connectWifi() {
if (!WiFi.config(local_IP, gateway, subnet, primaryDNS, secondaryDNS)) {
ESP_LOGD(MOUDLENAME,"STA Failed to configure");
}
//if (!WiFi.config(local_IP, gateway, subnet, primaryDNS, secondaryDNS)) {
// ESP_LOGD(MOUDLENAME,"STA Failed to configure");
//}
//设置wifi帐号密码
WiFi.begin(ssid, password);
@ -132,7 +133,7 @@ void FoodCube::connectWifi() {
macAdd.replace(":", ""); //板子的物理地址 并且去除冒号
log("macAdd: ");
logln(macAdd);
playText("[v1]网络连接成功");
playText("网络连接成功");
delay(500);
*/
}
@ -154,7 +155,7 @@ bool FoodCube::checkWiFiStatus()
macAdd.replace(":", ""); //板子的物理地址 并且去除冒号
log("macAdd: ");
logln(macAdd);
playText("[v1]网络连接成功");
playText("网络连接成功");
}
return wificonnected;
}
@ -177,11 +178,9 @@ void FoodCube::connectMqtt(String topicSub[], int topicSubCount) {
logln(macAdd);
/*连接成功 订阅主题*/
//订阅主题 PS:连接上mqtt服务器 订阅主题 收到信息触发回调函数 receiveCallback
for (int i = 0; i < topicSubCount; i++) { //遍历 订阅主题
subscribeTopic(topicSub[i], 1);
}
subscribeTopic("cmd", 1);
delay(500);
playText("[v1]服务器已连接");
playText("服务器已连接");
} else {
//失败返回状态码
log("MQTT Server Connect Failed. Client State:");
@ -258,16 +257,32 @@ void FoodCube::SWrite(uint8_t buf[], int len, uint8_t swSerial) {
}
}
void FoodCube::SetplayvolMax()
{
//输出音量开到最大
uint8_t volcommand[10]={0xFD,0x00,0x07,0x01,0x01,0x5B,0x76,0x31,0x30,0x5D};
SWrite(volcommand, sizeof(volcommand), voiceSerial);
}
/**
* @description:
* @param {String} str
*/
void FoodCube::playText(String str) {
// str="[v10]"+str;
void FoodCube::playText(String str,bool flying) {
String vstr;
//输出音量开到最大
// uint8_t volcommand[10]={0xFD,0x00,0x07,0x01,0x01,0x5B,0x76,0x31,0x30,0x5D};
// SWrite(volcommand, sizeof(volcommand), voiceSerial);
//字符串里面的音量
//空中音量开到最大,地面防止刺耳开到小
if (flying)
vstr="[v9]"+str;
else
vstr="[v1]"+str;
//return ;
/*消息长度*/
int len = str.length(); //修改信息长度 消息长度
int len = vstr.length(); //修改信息长度 消息长度
// if (len >= 3996) { //限制信息长度 超长的不播放
// return;
// }
@ -285,8 +300,8 @@ void FoodCube::playText(String str) {
command[index++] = 0x01;
command[index++] = 0x04;
/*帧命令 消息段*/
for (int i = 0; i < str.length(); i++) {
command[index++] = (int)str[i];
for (int i = 0; i < vstr.length(); i++) {
command[index++] = (int)vstr[i];
}
logln("playText");
/*

View File

@ -55,7 +55,8 @@ public:
/*串口输出*/
void SWrite(uint8_t buf[], int len, uint8_t swSerial);
/*声音模块控制*/
void playText(String str);
void playText(String str,bool flying=false);
void SetplayvolMax();
uint8_t chekVoiceMcu();
void stopVoice();
/*mavlink*/

View File

@ -3,7 +3,8 @@
// 定义公共结构,变量,硬件接口等
///
//
#define VERSION "0.90" //版本
#define VERSION "0.90" //软件版本
#define VERSION_HW 1 //硬件版本1:第一块硬件 2:目前版本
// 硬件接口定义////////////////////////////
// 按钮
#define BTN_UP 23 // 收线开关 接线BTN_UP---GND
@ -17,20 +18,31 @@
#define SERVO_PIN 14 // 锁定舵机PWM控制脚
////LED
#define LED_DATA_PIN 25
// Moto-CAN
#define MOTO_CAN_RX 26 //1号机 26 后面 27
#define MOTO_CAN_TX 27 //1号机 27 后面 26
#if (VERSION_HW == 1)
// Moto-CAN //第一版本硬件参数---1号机使用
#define MOTO_CAN_RX 26
#define MOTO_CAN_TX 27
#define WEIGHT_SCALE 165 // //A通道是165,B通道是41
#define HX711_GAIN 128
#else
// Moto-CAN //第二版本硬件参数---2号机使用
#define MOTO_CAN_RX 27 //PCB画板需要做了调整
#define MOTO_CAN_TX 26 //PCB画板需要做了调整
#define WEIGHT_SCALE 41 // 减少零点漂移用B通道是41
#define HX711_GAIN 32 //减少零点漂移用B通道的感度
#endif
///serial1
#define SERIAL_REPORT_TX 5
#define SERIAL_REPORT_RX 18
/////
#define WEIGHT_SCALE 165 // 276 //这是缩放值根据砝码实测516.f
//#define WEIGHT_SCALE 41 // //A通道是165,B通道是41
#define TM_INSTORE_WEIGHT_DELAY 200 //200 // 入仓动力延时关闭时间 ms
#define TM_INSTORE_DELAY_WEIGHT 200 // 入仓动力延时关闭时间生效的重量(g),免得空钩也延时关闭导致线拉紧 ms
#define TM_INSTORE_NOWEIGHT_DELAY 50 // 空钩完全不延时也可能顶部按键按不下去,加一点延时 ms
enum HookStatus
{
HS_UnInit, // 还未初始化

View File

@ -111,12 +111,12 @@ const uint16_t MAV_CMD_FC_DESCENTSTART=44; //飞开始下降,需要调整相
/*项目对象*/
//char* ssid = "szdot"; //wifi帐号
//char* password = "Ttaj@#*.com"; //wifi密码
char* ssid = (char*)"flicube"; //wifi帐号 "flicube";// "fxmf_sc01"
char* password = (char*)"fxmf0622"; //wifi密码 "fxmf0622"; //"12345678"
char* ssid = (char*)"fxmf_sc01"; //wifi帐号 "flicube";// "fxmf_sc01"
char* password = (char*)"12345678"; //wifi密码 "fxmf0622"; //"12345678"
char* mqttServer = (char*)"114.115.137.239";//"szdot.top"; //114.115.137.239 mqtt地址
int mqttPort = 1883; //mqtt端口
char* mqttName = (char*)"admin"; //mqtt帐号
char* mqttPassword = (char*)"1234567"; //mqtt密码
char* mqttPassword = (char*)"123456"; //mqtt密码
uint8_t mavlinkSerial = 2; //飞控占用的串口号
uint8_t voiceSerial = 1; //声音模块占用串口
char* udpServerIP = (char*) "192.168.8.210"; //云台相机ip
@ -136,7 +136,7 @@ String topicSub[] = { "questAss", "setPlaneState", "getPlaneState", "resetState"
int topicSubCount = sizeof(topicSub) / sizeof(topicSub[0]); //订阅主题总数
/*有更新主动发送 主题*/
//0:心跳信息 1:电压信息 2:电流信息 3:电池电量 4:高度信息 5:对地速度 6:卫星数量 7:纬度 8:经度 9:定位状态 10:飞机状态 11:网速测试 12:飞机模式,13:负载重量(g),14钩子状态,15:位置(经纬度,海拔高度)
String topicPub[] = { "heartBeat", "voltagBattery", "currentBattery", "batteryRemaining", "positionAlt", "groundSpeed", "satCount", "latitude", "longitude", "fixType", "planeState", "pingNet", "getPlaneMode","loadweight","hookstatus","position"};
String topicPub[] = { "heartBeat", "voltagBattery", "currentBattery", "batteryRemaining", "positionAlt", "groundSpeed", "satCount", "latitude", "longitude", "fixType", "state", "pingNet", "getPlaneMode","loadweight","hookstatus","position"};
int topicPubCount = sizeof(topicPub) / sizeof(topicPub[0]); //发送主题总数
String topicPubMsg[16]; //发送数据存放 对应topicPub
String oldMsg[16]; //记录旧的数据 用来对比有没有更新
@ -206,7 +206,7 @@ void setup()
/////////////////////////////////MQTT_语音_MAVLINK 部分
/*初始化*/
Serial1.begin(115200, SERIAL_8N1, SERIAL_REPORT_RX, SERIAL_REPORT_TX); //声音模块引串口脚映射
fc.playText("[v1]开始启动");
fc.playText("开始启动");
fc.connectWifi(); //连接wifi
// fc.playText("正在连接服务器");
// fc.connectMqtt(topicSub, topicSubCount); //连接mqtt
@ -254,7 +254,7 @@ void checkstatus()
if (abs(pullweight) > 100)
_checkweighttimes++;
else _checkweighttimes=0;
ESP_LOGD(MOUDLENAME,"check neet tare %d ",pullweight);
//ESP_LOGD(MOUDLENAME,"check neet tare %d ",pullweight);
if (_checkweighttimes>10)
{
_checkweightcal=false;
@ -279,7 +279,7 @@ void showinfo()
// moto_measure_t mf=motocontrol.getmotoinfo() ;
// printf("total_cnt:%.3f;speed:%.2f,curr:%.2fA \n ", mf.output_round_cnt, mf.output_speed_rpm,(float)mf.real_current/1000.0f);
// if (pullweight > 10)
// printf("PullWeight:%d\n", pullweight);
// printf("PullWeight:%d\n", pullweight); //发送重量到mqtt
topicPubMsg[14]=motocontrol.gethooktatus_str() ;
topicPubMsg[13]=pullweight;
@ -390,7 +390,7 @@ void checkinited()
scale.set_offset(wei_offset);
motocontrol.weightalign(true);
_needweightalign = false;
fc.playText("[v1]挂钩已锁定");
// fc.playText("挂钩已锁定");
initstatus = IS_OK;
}else
{
@ -404,7 +404,7 @@ void checkinited()
{
if (_weightalign_status==WAS_AlignOK)
{
fc.playText("[v1]挂钩已锁定");
// fc.playText("挂钩已锁定");
initstatus = IS_OK;
}else
if (_weightalign_status==WAS_Alignfault)
@ -458,6 +458,12 @@ void checkinited()
*/
}
}
void set_locked(bool locked)
{
motocontrol.setlocked(locked);
if (locked)
fc.playText("挂钩已锁定");
}
// 在核心1上执行重要的延迟低的
void loop()
{
@ -485,7 +491,7 @@ void loop()
if ((millis() - _tm_bengstop) > TM_INSTORE_WEIGHT_DELAY)
{
_bengstop = false;
motocontrol.setlocked(true);
set_locked(true);
}
}
else
@ -493,7 +499,7 @@ void loop()
if ((millis() - _tm_bengstop) > TM_INSTORE_NOWEIGHT_DELAY)
{
_bengstop = false;
motocontrol.setlocked(true);
set_locked(true);
}
}
}
@ -511,7 +517,7 @@ void loop()
void Task1(void *pvParameters)
{
// 初始化称重传感器
scale.begin(LOADCELL_DOUT_PIN, LOADCELL_SCK_PIN);
scale.begin(LOADCELL_DOUT_PIN, LOADCELL_SCK_PIN,HX711_GAIN); //2号机用的B通道,1号用的A通道
scale.set_scale(WEIGHT_SCALE); // 这是缩放值根据砝码实测516.f
scale.tare(); // 重置为0
@ -671,7 +677,7 @@ void ctbtn_pressstart()
void ctbtn_pressend()
{
ESP_LOGD(MOUDLENAME,"Top_pressend");
motocontrol.setlocked(false);
set_locked(false);
_bengstop = false;
}
@ -693,7 +699,7 @@ void down_action(float motospeed,float length = 0.0f)
{
motocontrol.setspeed(motospeed);
motocontrol.moto_run(MotoStatus::MS_Down,length);
fc.playText("[v1]放线");
fc.playText("放线");
}
}
}
@ -707,7 +713,7 @@ void up_action(float motospeed)
motocontrol.stopautodown(); //终止自动放线
motocontrol.setspeed(motospeed);
motocontrol.moto_run(MotoStatus::MS_Up);
fc.playText("[v1]收线");
fc.playText("收线");
}else
motocontrol.stoprun();
}
@ -768,7 +774,7 @@ void btn_presssatonce()
{
ESP_LOGD(MOUDLENAME,"UP_presssatonce");
led_show(255,255, 255); // 高亮一下
fc.playText("[v1]发送对频信息");
fc.playText("发送对频信息");
fc.pubMQTTmsg(topicHandle[0], fc.getMacAdd());
}
// 收线按钮-长按
@ -1126,7 +1132,7 @@ void mavlink_receiveCallback(uint8_t c) {
// 通过msgid来判断 数据流的类别
char buf[10];
//printf("mav_id:%d\n",msg.msgid);
// printf("mav_id:%d\n",msg.msgid);
switch (msg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT: // #0: Heartbeat 心跳
@ -1140,7 +1146,7 @@ void mavlink_receiveCallback(uint8_t c) {
if (!curr_armed)
{
ESP_LOGD(MOUDLENAME,"armed");
fc.playText("[v1]已解锁");
fc.playText("已解锁");
}
curr_armed=true;
topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 4, 1); //设置飞机状态为已解锁状态 1xxxx 第四位为1 代表已解锁
@ -1148,7 +1154,7 @@ void mavlink_receiveCallback(uint8_t c) {
if (curr_armed)
{
ESP_LOGD(MOUDLENAME,"disarm");
fc.playText("[v1]已加锁");
fc.playText("已加锁");
}
curr_armed=false; //心跳里面 判断没有解锁
topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 4, 0); //设置飞机状态为已解锁状态 0xxxx 第四位为0 代表未解锁
@ -1210,7 +1216,7 @@ void mavlink_receiveCallback(uint8_t c) {
}
break;
}
fc.playText(topicPubMsg[12]);
fc.playText(topicPubMsg[12],true);
}
}
break;
@ -1405,7 +1411,7 @@ void mavlink_receiveCallback(uint8_t c) {
Hook_autodown(rngalt_cm);
//最大音量语音播报1次
if (fc.questVoiceStr!="")
fc.playText("[v10]"+fc.questVoiceStr);
fc.playText(fc.questVoiceStr,true);
}
else
{
@ -1457,8 +1463,11 @@ void mavlink_receiveCallback(uint8_t c) {
* @description: 线
*/
void pubThread() {
/*解析mavlink 数据流等 此函数内会把解析的数据按信息类型 发布到对应主题*/
for (int i = 0; i < topicPubCount; i++) { //遍历向订阅主题 有数据更新时 发送信息
/*解析mavlink 数据流等 此函数内会把解析的数据按信息类型 发布到mqtt服务器 planeState/macadd主题 */
// 创建一个JSON对象
DynamicJsonDocument doc(2000); // 2000字节 缓冲区
//遍历 有更新的数据 组成一个json对象
for (int i = 0; i < topicPubCount; i++) {
if (topicPubMsg[i] != oldMsg[i]) {
if (i == 0) { //心跳包 每每向心跳主题发布信息
//启动飞控 第一次心跳 ps:防止飞控 滞后启动 拿不到数据
@ -1466,15 +1475,18 @@ void pubThread() {
fc.setIsInit(false);
fc.mav_request_data(); //再向飞控请求一次 设定飞控输出数据流内容
}
//发送心跳包
fc.pubMQTTmsg(topicPub[0], topicPubMsg[0]);
// printf("pub%s:%s\n",topicPub[0],topicPubMsg[0]);
} else { //非心跳包 有更新才向对应主题发布信息
fc.pubMQTTmsg(topicPub[i], topicPubMsg[i]);
//设置对象成员 ps:心跳
doc[topicPub[0]] = topicPubMsg[0];
} else { //非心跳 有更新 录入成员
doc[topicPub[i]] = topicPubMsg[i];
oldMsg[i] = topicPubMsg[i];
}
}
}
// 将JSON对象序列化为JSON字符串
String jsonString;
serializeJson(doc, jsonString);
fc.pubMQTTmsg("planeState", jsonString);
/*更新4G网络测速ping值*/
//pingNetTest();
}