ros+科大迅飞语音包+图灵机器人(二)在ros上使用科大迅飞
-
在工作空间catkin_ws下创建一个包
-
$ cd catkin_ws/src/
-
$ catkin_create_pkg voice_system std_msgs rospy roscpp
-
把科大迅飞包里的代码复制到你创建的包里,并重命名为xf_tts.cpp
- $ cd SoftWare/samples/tts_sample/
- $ cp tts_sample.c ~/catkin_ws/src/voice_system/src/
- $ cd catkin_ws/src/voice_system/src/
- $ mv tts_sample.c xf_tts.cpp
-
到SoftWare/include目录下把include拷贝到voice_system包下
- $ cd SoftWare/include
- $ cp * ~/catkin_ws/src/voice_system/include
-
修改xf_tts.cpp文件(注意要把appid改为自己的appid,gtts.h等路径要改为自己该文件的路径)
- xf_tts.cpp的代码如下
-
-
/* -
* 语音合成(Text To Speech,TTS)技术能够自动将任意文字实时转换为连续的 -
* 自然语音,是一种能够在任何时间、任何地点,向任何人提供语音信息服务的 -
* 高效便捷手段,非常符合信息时代海量数据、动态更新和个性化查询的需求。 -
*/ -
#include <stdlib.h> -
#include <stdio.h> -
#include <unistd.h> -
#include <errno.h> -
#include <ros/ros.h> -
#include <std_msgs/String.h> -
#include "/home/fan/SoftWare/include/qtts.h" -
#include "/home/fan/SoftWare/include/msp_cmn.h" -
#include "/home/fan/SoftWare/include/msp_errors.h" -
const char* fileName="/home/fan/music/voice.wav"; -
const char* playPath="play /home/fan/music/voice.wav"; -
typedef int SR_DWORD; -
typedef short int SR_WORD ; -
/* 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("\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; -
} -
int makeTextToWav(const char* text, const char* filename){ -
int ret = MSP_SUCCESS; -
const char* login_params = "appid = 5b090780, work_dir = .";//登录参数,appid与msc库绑定,请勿随意改动 -
/* -
* rdn: 合成音频数字发音方式 -
* volume: 合成音频的音量 -
* pitch: 合成音频的音调 -
* speed: 合成音频对应的语速 -
* voice_name: 合成发音人 -
* sample_rate: 合成音频采样率 -
* text_encoding: 合成文本编码格式 -
* -
*/ -
const char* session_begin_params = "engine_type = local,voice_name=xiaofeng, text_encoding = UTF8, tts_res_path = fo|res/tts/xiaofeng.jet;fo|res/tts/common.jet, sample_rate = 16000, speed = 50, volume = 50, pitch = 50, rdn = 0"; -
/* 用户登录 */ -
ret = MSPLogin(NULL, NULL, login_params); //第一个参数是用户名,第二个参数是密码,第三个参数是登录参数,用户名和密码可在http://www.xfyun.cn注册获取 -
if (MSP_SUCCESS != ret) -
{ -
printf("MSPLogin failed, error code: %d.\n", ret); -
} -
else{ -
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"); -
} -
MSPLogout(); -
return 0; -
} -
void playWav() -
{ -
system(playPath); -
} -
void topicCallBack(const std_msgs::String::ConstPtr& msg) -
{ -
std::cout<<"get topic text:" << msg->data.c_str(); -
makeTextToWav(msg->data.c_str(),fileName); -
playWav(); -
} -
int main(int argc, char* argv[]) -
{ const char* start= "科大迅飞在线语音合成模块启动"; -
makeTextToWav(start,fileName); -
playWav(); -
ros::init(argc,argv, "xf_tts_node"); -
ros::NodeHandle n; -
ros::Subscriber sub = n.subscribe("/voice/xf_tts_topic", 3,topicCallBack); -
ros::spin(); -
return 0; -
}
-
-
在CMakeList文件的“include_directories”后加入“include”,在文件末尾加入
-
-
add_executable(xf_tts_node src/xf_tts.cpp) -
target_link_libraries(xf_tts_node ${catkin_LIBRARIES} -lmsc -lrt -ldl -lpthread)
-
- CMakeList代码
-
-
cmake_minimum_required(VERSION 2.8.3) -
project(voice_system) -
find_package(catkin REQUIRED COMPONENTS -
roscpp -
rospy -
std_msgs -
) -
include_directories( -
include -
${catkin_INCLUDE_DIRS} -
) -
add_executable(xf_tts_node src/xf_tts.cpp) -
target_link_libraries(xf_tts_node ${catkin_LIBRARIES} -lmsc -lrt -ldl -lpthread)
-
- 在此时到catkin_ws下进行编译
- $ catkin_make
- 编译完后,roscore一下,重新打开窗口到catkin_ws下运行xf_tts_node节点
- $ cd catkin_ws
- $ rosrun voice_system xf_tts_node
- 此时,你能听到,“科大迅飞语音模块启动”的声音“
- 重新打开一个命令窗口,在catkin_ws下发布一个话题
- $ cd catkin_ws
- $ rostopic pub /voice/xf_tts_topic std_msgs/String 你好
- 此时,你会听到”你好的声音“
- 证明ros上运行科大迅飞语音模块成功