机器人语音交互
一、讯飞开放平台
讯飞开放平台文档中心介绍了SDK的使用。我们需要下载讯飞SDK,以用于语音识别。
讯飞SDK的samples如下;

在ubuntu系统中拷贝并安装库命令如下:
sudo cp libmsc.so /usr/lib/
sudo apt install sox
sudo apt install libsox-fmt-all
二、语音交互
通过语音控制机器人运动场景:
- 通过“向前”、“向后”、“向左”、“向右”、“停止”等语音命令,控制机器人的运动。
2.1 思路
通过iat_online_record_sample识别语音,然后对翻译出的文字进行关键字词的识别,不同的关键词对应小车的不同运动状态。最后还可以加入tts_online_sample,添加语音对话的趣味功能。
通过麦克风获取语音信号data,之后小车的控制规则如下:
if (data 包含 ‘前’ ):
小车前进
else if (data 包含 ‘后’):
小车后退
else if (data 包含 ‘左’):
小车左转
else:if (data 包含 ‘右’):
小车右转
else:if (data 包含 ‘停’ ):
小车停止
2.2 基于语音控制小车
使用讯飞语音库,创建robot_voice功能包。
roslaunch mbot_gazebo view_mbot_gazebo_empty_world_automobile.launch // 启动小车模型
roslaunch robot_voice voice_control_automobile.launch // 启动语音读取,翻译功能包
voice_control_automobile.launch内容如下:
<launch>
<node name="iat_publish" pkg="robot_voice" type="iat_publish" output="screen"/>
<node name="voice_control" pkg="robot_voice" type="voice_control" output="screen"/>
</launch>
核心功能文件voice_control.cpp内容如下:
/*
* 语音合成(Text To Speech,TTS)技术能够自动将任意文字实时转换为连续的
* 自然语音,是一种能够在任何时间、任何地点,向任何人提供语音信息服务的
* 高效便捷手段,非常符合信息时代海量数据、动态更新和个性化查询的需求。
*/
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <unistd.h>
#include "robot_voice/qtts.h"
#include "robot_voice/msp_cmn.h"
#include "robot_voice/msp_errors.h"
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "geometry_msgs/Twist.h"
/* wav音频头部格式 */
typedef struct _wave_pcm_hdr
{
char riff[4]; // = "RIFF"
int size_8; // = FileSize - 8
char wave[4]; // = "WAVE"
char fmt[4]; // = "fmt "
int fmt_size; // = 下一个结构体的大小 : 16
short int format_tag; // = PCM : 1
short int channels; // = 通道数 : 1
int samples_per_sec; // = 采样率 : 8000 | 6000 | 11025 | 16000
int avg_bytes_per_sec; // = 每秒字节数 : samples_per_sec * bits_per_sample / 8
short int block_align; // = 每采样点字节数 : wBitsPerSample / 8
short int bits_per_sample; // = 量化比特数: 8 | 16
char data[4]; // = "data";
int data_size; // = 纯数据长度 : FileSize - 44
} wave_pcm_hdr;
/* 默认wav音频头部数据 */
wave_pcm_hdr default_wav_hdr =
{
{ 'R', 'I', 'F', 'F' },
0,
{'W', 'A', 'V', 'E'},
{'f', 'm', 't', ' '},
16,
1,
1,
16000,
32000,
2,
16,
{'d', 'a', 't', 'a'},
0
};
/* 文本合成 */
int text_to_speech(const char* src_text, const char* des_path, const char* params)
{
int ret = -1;
FILE* fp = NULL;
const char* sessionID = NULL;
unsigned int audio_len = 0;
wave_pcm_hdr wav_hdr = default_wav_hdr;
int synth_status = MSP_TTS_FLAG_STILL_HAVE_DATA;
if (NULL == src_text || NULL == des_path)
{
printf("params is error!\n");
return ret;
}
fp = fopen(des_path, "wb");
if (NULL == fp)
{
printf("open %s error.\n", des_path);
return ret;
}
/* 开始合成 */
sessionID = QTTSSessionBegin(params, &ret);
if (MSP_SUCCESS != ret)
{
printf("QTTSSessionBegin failed, error code: %d.\n", ret);
fclose(fp);
return ret;
}
ret = QTTSTextPut(sessionID, src_text, (unsigned int)strlen(src_text), NULL);
if (MSP_SUCCESS != ret)
{
printf("QTTSTextPut failed, error code: %d.\n",ret);
QTTSSessionEnd(sessionID, "TextPutError");
fclose(fp);
return ret;
}
printf("正在合成 ...\n");
fwrite(&wav_hdr, sizeof(wav_hdr) ,1, fp); //添加wav音频头,使用采样率为16000
while (1)
{
/* 获取合成音频 */
const void* data = QTTSAudioGet(sessionID, &audio_len, &synth_status, &ret);
if (MSP_SUCCESS != ret)
break;
if (NULL != data)
{
fwrite(data, audio_len, 1, fp);
wav_hdr.data_size += audio_len; //计算data_size大小
}
if (MSP_TTS_FLAG_DATA_END == synth_status)
break;
printf(">");
usleep(150*1000); //防止频繁占用CPU
}
printf("\n");
if (MSP_SUCCESS != ret)
{
printf("QTTSAudioGet failed, error code: %d.\n",ret);
QTTSSessionEnd(sessionID, "AudioGetError");
fclose(fp);
return ret;
}
/* 修正wav文件头数据的大小 */
wav_hdr.size_8 += wav_hdr.data_size + (sizeof(wav_hdr) - 8);
/* 将修正过的数据写回文件头部,音频文件为wav格式 */
fseek(fp, 4, 0);
fwrite(&wav_hdr.size_8,sizeof(wav_hdr.size_8), 1, fp); //写入size_8的值
fseek(fp, 40, 0); //将文件指针偏移到存储data_size值的位置
fwrite(&wav_hdr.data_size,sizeof(wav_hdr.data_size), 1, fp); //写入data_size的值
fclose(fp);
fp = NULL;
/* 合成完毕 */
ret = QTTSSessionEnd(sessionID, "Normal");
if (MSP_SUCCESS != ret)
{
printf("QTTSSessionEnd failed, error code: %d.\n",ret);
}
return ret;
}
std::string to_string(int val)
{
char buf[20];
sprintf(buf, "%d", val);
return std::string(buf);
}
ros::Publisher control_commond_pub;
float pre_linear_x = 0, pre_angular_z = 0; //记录上一个小车状态
void voiceWordsCallback(const std_msgs::String::ConstPtr& msg)
{
char cmd[2000];
int ret = MSP_SUCCESS;
const char* session_begin_params = "voice_name = xiaoyan, text_encoding = utf8, sample_rate = 16000, speed = 50, volume = 50, pitch = 50, rdn = 2";
const char* filename = "tts_sample.wav"; //合成的语音文件名称
const char* text;
std::cout<<"I heard :"<<msg->data.c_str()<<std::endl;
text = msg->data.c_str();
// 初始化geometry_msgs::Twist类型的消息
geometry_msgs::Twist Twist_msg;
float linear_x, angular_z;
std::string dataString = msg->data;
if(dataString.find("前") != std::string::npos)
{
char frontString[100] = "我要往前开了,前进";
text = frontString;
std::cout<<text<<std::endl;
linear_x = 0.1;
angular_z = pre_angular_z;
}
else if( dataString.find("后") != std::string::npos)
{
char backString[100] = "go go,向后了";
text = backString;
std::cout<<text<<std::endl;
linear_x = -0.1;
angular_z = pre_angular_z;
}
else if(dataString.find("左") != std::string::npos)
{
char leftString[100] = "你现在向左";
text = leftString;
std::cout<<text<<std::endl;
angular_z = -0.5;
linear_x = pre_linear_x;
}
else if(dataString.find("右") != std::string::npos)
{
char rightString[100] = "你现在youguai";
text = rightString;
std::cout<<text<<std::endl;
angular_z = 0.5;
linear_x = pre_linear_x;
}
else if( dataString.find("停") != std::string::npos)
{
char stopString[40] = "停停停停停停停停停停停";
text = stopString;
std::cout<<text<<std::endl;
linear_x = 0;
angular_z = 0;
}
else
{
text = msg->data.c_str();
linear_x = pre_linear_x;
angular_z = pre_angular_z;
}
Twist_msg.linear.x = linear_x;
Twist_msg.angular.z = angular_z;
pre_linear_x = linear_x;
pre_angular_z = angular_z;
/* 文本合成 */
printf("开始合成 ...\n");
ret = text_to_speech(text, filename, session_begin_params);
if (MSP_SUCCESS != ret)
{
printf("text_to_speech failed, error code: %d.\n", ret);
}
printf("合成完毕\n");
popen("play tts_sample.wav", "r");
// 发布消息
ROS_INFO("I heard cmd_vel linear.x:[%f] angular.z:[%f]",linear_x, angular_z);
control_commond_pub.publish(Twist_msg);
sleep(1);
}
void toExit()
{
printf("按任意键退出 ...\n");
getchar();
MSPLogout(); //退出登录
}
int main(int argc, char* argv[])
{
int ret = MSP_SUCCESS;
const char* login_params = "appid = 5d60d836, work_dir = .";//登录参数,appid与msc库绑定,请勿随意改动
/*
* rdn: 合成音频数字发音方式
* volume: 合成音频的音量
* pitch: 合成音频的音调
* speed: 合成音频对应的语速
* voice_name: 合成发音人
* sample_rate: 合成音频采样率
* text_encoding: 合成文本编码格式
*
*/
/* 用户登录 */
ret = MSPLogin(NULL, NULL, login_params);//第一个参数是用户名,第二个参数是密码,第三个参数是登录参数,用户名和密码可在http://www.xfyun.cn注册获取
if (MSP_SUCCESS != ret)
{
printf("MSPLogin failed, error code: %d.\n", ret);
// goto exit ;//登录失败,退出登录
toExit();
}
printf("\n###########################################################################\n");
printf("## 语音合成(Text To Speech,TTS)技术能够自动将任意文字实时转换为连续的 ##\n");
printf("## 自然语音,是一种能够在任何时间、任何地点,向任何人提供语音信息服务的 ##\n");
printf("## 高效便捷手段,非常符合信息时代海量数据、动态更新和个性化查询的需求。 ##\n");
printf("###########################################################################\n\n");
ros::init(argc,argv,"TextToSpeech");
ros::NodeHandle n;
// 创建一个Publisher,发布名为/cmd_vel的topic,消息类型为geometry_msgs::Twist
control_commond_pub = n.advertise<geometry_msgs::Twist>("/cmd_vel", 1000);
ros::Subscriber sub =n.subscribe("voiceWords", 1000, voiceWordsCallback);
ros::spin();
return 0;
}
最后运行效果如下:



浙公网安备 33010602011771号