以上节tts语音输出为例
下载sdk链接:http://www.xfyun.cn/sdk/dispatcher
1、下载SDK,解压;
2、在ROS工作空间下创建一个Package;
catkin_create_pkg tts_voice roscpp rospy std_msgs
3、将SDK文件夹中的头文件,即下载的SDK文件夹中include文件夹下的 .h文件拷贝至tts_voice/include/下;
4、将SDK文件夹中sample/tts_sample中的xf_tts.cpp文件拷贝至tts_voice/src/下;
5、将SDK文件夹中libs/x64/libmsc.so文件拷贝至/user/libs/下;
6、打开CMakelist,
1)修改include_directories为:即包括拷贝的头文件所在的include目录
include_directories(
${catkin_INCLUDE_DIRS}
include
)
2)添加:
add_executable(tts_voice_node src/xf_tts.cpp)
target_link_libraries(tts_voice_node
${catkin_LIBRARIES} -lmsc -lrt -ldl -lpthread
)
# 生成可执行文件
# 添加链接库,其中动态链接库路径按实际修改
CmakeLists.txt
cmake_minimum_required(VERSION 2.8.3) project(tts_voice) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs ) catkin_package( # INCLUDE_DIRS include # LIBRARIES tts_voice # CATKIN_DEPENDS roscpp rospy std_msgs # DEPENDS system_lib ) ########### ## Build ## ########### ## Specify additional locations of header files ## Your package locations should be listed before other locations # include_directories(include) include_directories( ${catkin_INCLUDE_DIRS} include ) ## Declare a C++ executable add_executable(tts_voice_node src/xf_tts.cpp) ## Specify libraries to link a library or executable target against target_link_libraries(tts_voice_node ${catkin_LIBRARIES} -lmsc -lrt -ldl -lpthread )
xf_tts.cpp源文件
/* * 语音合成(Text To Speech,TTS)技术能够自动将任意文字实时转换为连续的 * 自然语音,是一种能够在任何时间、任何地点,向任何人提供语音信息服务的 * 高效便捷手段,非常符合信息时代海量数据、动态更新和个性化查询的需求。 */ #include#include "std_msgs/String.h" #include #include <string.h> #include #include #include "qtts.h" #include "msp_cmn.h" #include "msp_errors.h" const char* FileName = "/home/cam/Music/voice.wav"; const char* PlayPath = "play /home/cam/Music/voice.wav"; /* 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(15*1000); //防止频繁占用CPU }//合成状态synth_status取值请参阅《讯飞语音云API文档》 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 = 57f49f64, work_dir = .";//登录参数,appid与msc库绑定,请勿随意改动 /* * rdn: 合成音频数字发音方式 * volume: 合成音频的音量 * pitch: 合成音频的音调 * speed: 合成音频对应的语速 * voice_name: 合成发音人 * sample_rate: 合成音频采样率 * text_encoding: 合成文本编码格式 * * 详细参数说明请参阅《讯飞语音云MSC--API文档》 */ const char* session_begin_params = "voice_name = xiaowanzi, text_encoding = utf8, sample_rate = 16000, speed = 50, volume = 50, pitch = 50, rdn = 0"; // const char* filename = "tts_sample.wav"; //合成的语音文件名称 // const char* text = "我是小丸子,今年126岁了,我的车牌号是12365,今年是2016年12月20号"; //合成文本 /* 用户登录 */ ret = MSPLogin(NULL, NULL, login_params);//第一个参数是用户名,第二个参数是密码,第三个参数是登录参数,用户名和密码可在http://open.voicecloud.cn注册获取 if (MSP_SUCCESS != ret) { printf("MSPLogin failed, error code: %d.\n", ret); goto exit ;//登录失败,退出登录 } /* 文本合成 */ 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"); exit: MSPLogout(); //退出登录 return 0; } /** * play the wav file **/ void PlayWav() { system(PlayPath); } /** *接受/voice/xf_tts_topic话题的字符串的回调函数 */ void TTSCallback(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,TTSCallback); ros::spin(); return 0; }
到~/catkin_ws编译
cam@cam-Aspire-V3-572G:~/catkin_ws$ catkin_make -j4
运行
¥ roscore
$ rosrun tts_voice tts_voice_node
启动播放 "宝宝启动成功了"
通过话题播放
rostopic pub /voice/xf_tts_topic std_msgs/String " 韩联社预计,鉴于黄教坚持现有外交政策,“萨德”部署相关工作可能提速。本月早些时候,一些政府消息人士透露,
由于总统朴槿惠遭弹劾,国内政 局不确定性增加,韩国国防部决定加快“萨德”的相关部署工作,最快可能在明年5月完成部署。根据消息人士的说法,为了能尽早完成部署工作,
韩国国防部甚至考虑省略掉环境影响评估的环节。"
使用时需要把
const char* login_params = "appid = 57f49f64, work_dir = .";//登录参数,appid与msc库绑定,请勿随意改动
appid改为自己的帐号
如果play播放音频出错,是因为没有安装sox
执行安装即可
sudo apt-get install sox