【类 型】:fix

【原  因】:1.飞机声音模块死机bug 在声音函数里面最后延迟300毫秒解决 2.播放声音函数第二个参数给位音量控制  V1 至 V9   3.mqtt监听playText 前端穿过来得声音json数据 并播放 4.送餐放钩时播放声音改为V9 最大声音
【过  程】:
【影  响】:

# 类型 包含:
# feat:新功能(feature)
# fix:修补bug
# docs:文档(documentation)
# style: 格式(不影响代码运行的变动)
# refactor:重构(即不是新增功能,也不是修改bug的代码变动)
# test:增加测试
# chore:构建过程或辅助工具的变动
This commit is contained in:
air 2025-05-13 20:08:44 +08:00
parent 408c52bf37
commit a571f30aa7
3 changed files with 152 additions and 142 deletions

View File

@ -265,58 +265,47 @@ void FoodCube::SetplayvolMax()
SWrite(volcommand, sizeof(volcommand), voiceSerial); SWrite(volcommand, sizeof(volcommand), voiceSerial);
} }
/** /**
* @description: * @brief
* @param {String} str * @param str UTF-8
* @param vol V1~V9 V1
*/ */
void FoodCube::playText(String str, bool flying) void FoodCube::playText(String str, VoiceVolume vol)
{ {
// 拼接音量控制前缀,例如 "[v5]起飞"
String vstr = "[v" + String((int)vol) + "]" + str;
String vstr; // 计算消息长度,语音模块要求帧数据 = 内容长度 + 2
// 输出音量开到最大 int len = vstr.length();
// uint8_t volcommand[10]={0xFD,0x00,0x07,0x01,0x01,0x5B,0x76,0x31,0x30,0x5D}; if (len >= 3996)
// SWrite(volcommand, sizeof(volcommand), voiceSerial);
// 字符串里面的音量
// 空中音量开到最大,地面防止刺耳开到小
if (flying)
vstr = "[v9]" + str;
else
vstr = "[v1]" + str;
// return ;
/*消息长度*/
int len = vstr.length(); // 修改信息长度 消息长度
// if (len >= 3996) { //限制信息长度 超长的不播放
// return;
// }
/*长度高低位*/
int frameLength = len + 2; // 5 bytes for header and length bytes
byte highByte = (frameLength >> 8) & 0xFF; // extract high byte of length
byte lowByte = frameLength & 0xFF; // extract low byte of length
/*帧命令头*/
uint8_t command[len + 5];
// 已知 帧头0xFD z信息长度高位 x信息长度低位 0x01命令字1是开始命令 0x04utf8编码 先给值
int index = 0;
command[index++] = 0xFD;
command[index++] = highByte;
command[index++] = lowByte;
command[index++] = 0x01;
command[index++] = 0x04;
/*帧命令 消息段*/
for (int i = 0; i < vstr.length(); i++)
{ {
command[index++] = (int)vstr[i]; // 防止超长导致模块错误
return;
} }
logln("playText");
/* int frameLength = len + 2;
log("sendplay:"); byte highByte = (frameLength >> 8) & 0xFF;
for (int i = 0; i < sizeof(command); i++) { byte lowByte = frameLength & 0xFF;
log(command[i]);
log(" "); // 构造完整命令帧:帧头 + 长度 + 命令 + 编码类型 + 内容
uint8_t command[len + 5];
int index = 0;
command[index++] = 0xFD; // 帧头
command[index++] = highByte; // 长度高位
command[index++] = lowByte; // 长度低位
command[index++] = 0x01; // 命令字:播放合成
command[index++] = 0x04; // 编码方式UTF-8
// 填充文本内容部分
for (int i = 0; i < len; i++)
{
command[index++] = (uint8_t)vstr[i];
} }
logln("");
*/ // 发送数据到语音串口
// 串口发送 播放声音
SWrite(command, sizeof(command), voiceSerial); SWrite(command, sizeof(command), voiceSerial);
// 延时等待模块处理,防止连续播放死机
delay(300); // 可根据模块处理时间调节
} }
/** /**

View File

@ -58,7 +58,20 @@ public:
void pubMQTTmsg(String topicString, String messageString); void pubMQTTmsg(String topicString, String messageString);
/*声音模块控制*/ /*声音模块控制*/
void playText(String str, bool flying = false); // 枚举,音量
enum VoiceVolume
{
V1 = 1,
V2 = 2,
V3 = 3,
V4 = 4,
V5 = 5,
V6 = 6,
V7 = 7,
V8 = 8,
V9 = 9
};
void playText(String str, VoiceVolume vol = V1);
void SetplayvolMax(); void SetplayvolMax();
uint8_t chekVoiceMcu(); uint8_t chekVoiceMcu();
void stopVoice(); void stopVoice();

View File

@ -90,6 +90,24 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length)
String todo = value; // 转换值 String todo = value; // 转换值
writeRoute(todo); // 写入航点 writeRoute(todo); // 写入航点
} }
else if (key == "playText")
{
JsonObject obj = value.as<JsonObject>(); // 获取嵌套的对象
String todo = obj["val"] | ""; // 获取文本内容,默认空字符串
int volInt = obj["vol"] | 1; // 获取音量默认1
// 转为枚举,确保在 1~9 范围内
volInt = constrain(volInt, 1, 9);
FoodCube::VoiceVolume volume = (FoodCube::VoiceVolume)volInt;
fc.playText(todo, volume); // 播放声音
}
else if (key == "questAss")
{ // 飞行航点任务 questAss
String todo = value; // 转换值
writeRoute(todo); // 写入航点
}
else if (key == "setQuestState") else if (key == "setQuestState")
{ {
// 设置飞机任务状态 // 设置飞机任务状态
@ -104,28 +122,22 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length)
topicPubMsg[10] = fc.setNBit(topicPubMsg[10], n, state); topicPubMsg[10] = fc.setNBit(topicPubMsg[10], n, state);
if (n = 5 && state == 1) // 执行任务 ps:切自动 if (n = 5 && state == 1) // 执行任务 ps:切自动
{ {
delay(3000);
// 切模式 // 切模式
set_mode(AUTO); // 设置飞控为自动模式 set_mode(AUTO); // 设置飞控为自动模式
// 油门 // 油门
uint16_t chan[] = {1500, 1500, 1500, 1500}; uint16_t chan[] = {1500, 1500, 1500, 1500};
int8_t i = 0; fc.mav_channels_override(chan); // 控制油门
while (topicPubMsg[12] == "自动" && i < 10)
{
fc.mav_channels_override(chan); // 控制油门
delay(50);
i++;
}
if (topicPubMsg[12] != "自动")
{
topicPubMsg[18] = "自动模式切换失败,请检查飞控是否正常工作"; // 终端 打印日志
}
} }
} }
else if (key == "unlock") // 解锁 else if (key == "unlock") // 解锁
{ {
set_mode(LOITER); // 设置飞控为定点模式 // 油门
delay(2000); // 可以根据需要调整延迟时间,确保模式切换生效 uint16_t chan[] = {1500, 1500, 1100, 1500}; // 加解锁 油门到底
lock_or_unlock(false); // 解锁 fc.mav_channels_override(chan); // 控制油门
set_mode(LOITER); // 设置飞控为定点模式
delay(2000); // 可以根据需要调整延迟时间,确保模式切换生效
lock_or_unlock(false); // 解锁
// 功能待修改 判断有没有在地面上 然后切定点 确认切定点油门设1100 // 功能待修改 判断有没有在地面上 然后切定点 确认切定点油门设1100
} }
else if (key == "lock") // 加锁 else if (key == "lock") // 加锁
@ -162,28 +174,18 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length)
} }
else if (key == "autoMode") // 自动auto模式 else if (key == "autoMode") // 自动auto模式
{ {
delay(3000);
// 切模式 // 切模式
set_mode(AUTO); // 设置飞控为定高模式 set_mode(AUTO); // 设置飞控为自动模式
// 油门 // 油门
uint16_t chan[] = {1500, 1500, 1500, 1500}; uint16_t chan[] = {1500, 1500, 1500, 1500};
int8_t i = 0; fc.mav_channels_override(chan); // 控制油门
while (topicPubMsg[12] == "自动" && i < 10)
{
fc.mav_channels_override(chan); // 控制油门
delay(50);
i++;
}
if (topicPubMsg[12] != "自动")
{
fc.playText("自动模式切换失败,请检查飞控是否正常工作");
}
} }
else if (key == "loiterMode") // 悬停定点loiter模式 else if (key == "loiterMode") // 悬停定点loiter模式
{ {
// 油门 // 油门
uint16_t chan[] = {1500, 1500, 1500, 1500}; // 加解锁 油门到底 uint16_t chan[] = {1500, 1500, 1500, 1500};
fc.mav_channels_override(chan); // 控制油门 fc.mav_channels_override(chan); // 控制油门
delay(500); delay(500);
// 切模式 // 切模式
set_mode(LOITER); // 设置飞控为定点模式 set_mode(LOITER); // 设置飞控为定点模式
@ -194,8 +196,8 @@ void mqtt_receiveCallback(char *topic, byte *payload, unsigned int length)
else if (key == "holdAltMode") // 定高 else if (key == "holdAltMode") // 定高
{ {
// 油门 // 油门
uint16_t chan[] = {1500, 1500, 1500, 1500}; // 加解锁 油门到底 uint16_t chan[] = {1500, 1500, 1500, 1500};
fc.mav_channels_override(chan); // 控制油门 fc.mav_channels_override(chan); // 控制油门
delay(500); delay(500);
// 切模式 // 切模式
set_mode(ALT_HOLD); set_mode(ALT_HOLD);
@ -442,9 +444,74 @@ void mavlink_receiveCallback(uint8_t c)
// mavlink_msg_rc_channels_decode(&msg, &rc_channels); // mavlink_msg_rc_channels_decode(&msg, &rc_channels);
// uint16_t throttle_value = rc_channels.chan3_raw; // ch3_raw 是油门通道的原始输 // uint16_t throttle_value = rc_channels.chan3_raw; // ch3_raw 是油门通道的原始输
// Serial.println(throttle_value); // if (topicPubMsg[18] != "油门:" + String(throttle_value))
// {
// topicPubMsg[18] = "油门:" + String(throttle_value); // 油门值
// }
// } // }
// break; // break;
case MAVLINK_MSG_ID_COMMAND_LONG: // #47: 航点提交成果反馈
{
uint16_t fc_hook_cmd = mavlink_msg_command_long_get_command(&msg);
uint16_t rngalt_cm = (uint16_t)mavlink_msg_command_long_get_param1(&msg);
// printf("COMMAND_LONG ID:%d,rng:%dcm \n", fc_hook_cmd, rngalt_cm);
topicPubMsg[18] = "COMMAND_LONG ID:" + String(fc_hook_cmd) + ",rng:" + String(rngalt_cm) + "cm"; // 终端 打印日志
switch (fc_hook_cmd)
{
// 自动放线
case MAV_CMD_FC_HOOK_AUTODOWN:
{
HookStatus hss = motocontrol.gethooktatus();
// printf("MAV_CMD_FC_HOOK_AUTODOWN Hook:%d,rng:%dcm \n", hss, rngalt_cm);
topicPubMsg[18] = "MAV_CMD_FC_HOOK_AUTODOWN Hook:" + String(hss) + ",rng:" + String(rngalt_cm) + "cm"; // 终端 打印日志
// 没有激光高度直接退出
if (rngalt_cm == 0)
{
rngalt_cm == 500;
// printf("exit rngalt_cm==0");
topicPubMsg[18] = "exit rngalt_cm==0激光高度异常";
// break;
}
if (hss == HS_Locked)
{
Hook_autodown(rngalt_cm);
topicPubMsg[18] = "Hook_autodown";
// 语音播报3次
if (fc.questVoiceStr != "")
{
fc.playText(fc.questVoiceStr + "" + fc.questVoiceStr + "" + fc.questVoiceStr, fc.V9);
}
}
else
{
if (hss == HS_Stop)
Hook_resume();
else
// printf("exit hooktatus error");
topicPubMsg[18] = "exit hooktatus error";
}
break;
}
// 暂停
case MAV_CMD_FC_HOOK_PAUSE:
{
// printf("MAV_CMD_FC_HOOK_PAUSE \n");
topicPubMsg[18] = "MAV_CMD_FC_HOOK_PAUSE";
Hook_stop();
break;
}
// 收线 收钩
case MAV_CMD_FC_HOOK_RECOVERY:
{
// printf("MAV_CMD_FC_HOOK_RECOVERY \n");
topicPubMsg[18] = "MAV_CMD_FC_HOOK_PAUSE";
Hook_recovery();
break;
}
}
}
break;
case MAVLINK_MSG_ID_HOME_POSITION: // #242 返航点位置 case MAVLINK_MSG_ID_HOME_POSITION: // #242 返航点位置
{ {
char buf[120]; char buf[120];
@ -526,7 +593,7 @@ void mavlink_receiveCallback(uint8_t c)
if (!curr_armed) if (!curr_armed)
{ {
printf("armed\n"); printf("armed\n");
fc.playText("[v1]已解锁"); fc.playText("已解锁");
} }
curr_armed = true; curr_armed = true;
topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 4, 1); // 设置飞机状态为已解锁状态 1xxxx 第四位为1 代表已解锁 topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 4, 1); // 设置飞机状态为已解锁状态 1xxxx 第四位为1 代表已解锁
@ -537,7 +604,7 @@ void mavlink_receiveCallback(uint8_t c)
if (curr_armed) if (curr_armed)
{ {
printf("disarm\n"); printf("disarm\n");
fc.playText("[v1]已加锁"); fc.playText("已加锁");
} }
curr_armed = false; // 心跳里面 判断没有解锁 curr_armed = false; // 心跳里面 判断没有解锁
topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 4, 0); // 设置飞机状态为未解锁状态 0xxxx 第四位为0 代表未解锁 topicPubMsg[10] = fc.setNBit(topicPubMsg[10], 4, 0); // 设置飞机状态为未解锁状态 0xxxx 第四位为0 代表未解锁
@ -560,7 +627,7 @@ void mavlink_receiveCallback(uint8_t c)
{ {
case 0: case 0:
{ {
topicPubMsg[12] = "姿态"; topicPubMsg[12] = "稳定";
} }
break; break;
case 2: case 2:
@ -580,7 +647,7 @@ void mavlink_receiveCallback(uint8_t c)
break; break;
case 5: case 5:
{ {
topicPubMsg[12] = "悬停"; // Loiter 定点 topicPubMsg[12] = "定点"; // Loiter 定点
} }
break; break;
case 6: case 6:
@ -605,7 +672,7 @@ void mavlink_receiveCallback(uint8_t c)
break; break;
} }
fc.playText(topicPubMsg[12]); fc.playText(topicPubMsg[12]);
topicPubMsg[18] = "飞控模式切换为" + topicPubMsg[12]; // 终端 打印日志 topicPubMsg[18] = "飞控模式切换为" + topicPubMsg[12]; // 终端 打印日志
} }
} }
break; break;
@ -811,65 +878,6 @@ void mavlink_receiveCallback(uint8_t c)
} }
break; break;
case MAVLINK_MSG_ID_COMMAND_LONG: // #47: 航点提交成果反馈
{
uint16_t fc_hook_cmd = mavlink_msg_command_long_get_command(&msg);
uint16_t rngalt_cm = (uint16_t)mavlink_msg_command_long_get_param1(&msg);
// printf("COMMAND_LONG ID:%d,rng:%dcm \n", fc_hook_cmd, rngalt_cm);
topicPubMsg[18] = "COMMAND_LONG ID:" + String(fc_hook_cmd) + ",rng:" + String(rngalt_cm) + "cm"; // 终端 打印日志
switch (fc_hook_cmd)
{
// 自动放线
case MAV_CMD_FC_HOOK_AUTODOWN:
{
HookStatus hss = motocontrol.gethooktatus();
// printf("MAV_CMD_FC_HOOK_AUTODOWN Hook:%d,rng:%dcm \n", hss, rngalt_cm);
topicPubMsg[18] = "MAV_CMD_FC_HOOK_AUTODOWN Hook:" + String(hss) + ",rng:" + String(rngalt_cm) + "cm"; // 终端 打印日志
// 没有激光高度直接退出
if (rngalt_cm == 0)
{
// printf("exit rngalt_cm==0");
topicPubMsg[18] = "exit rngalt_cm==0激光高度异常";
break;
}
if (hss == HS_Locked)
{
Hook_autodown(rngalt_cm);
topicPubMsg[18] = "Hook_autodown";
// 语音播报3次
if (fc.questVoiceStr != "")
fc.playText(fc.questVoiceStr + "" + fc.questVoiceStr + "" + fc.questVoiceStr);
}
else
{
if (hss == HS_Stop)
Hook_resume();
else
// printf("exit hooktatus error");
topicPubMsg[18] = "exit hooktatus error";
}
break;
}
// 暂停
case MAV_CMD_FC_HOOK_PAUSE:
{
// printf("MAV_CMD_FC_HOOK_PAUSE \n");
topicPubMsg[18] = "MAV_CMD_FC_HOOK_PAUSE";
Hook_stop();
break;
}
// 收线 收钩
case MAV_CMD_FC_HOOK_RECOVERY:
{
// printf("MAV_CMD_FC_HOOK_RECOVERY \n");
topicPubMsg[18] = "MAV_CMD_FC_HOOK_PAUSE";
Hook_recovery();
break;
}
}
}
break;
case MAVLINK_MSG_ID_PARAM_VALUE: // #22:获取飞控参数信息 case MAVLINK_MSG_ID_PARAM_VALUE: // #22:获取飞控参数信息
{ {
mavlink_param_value_t param_value; mavlink_param_value_t param_value;