大家好,欢迎来到IT知识分享网。
第一步:注册;
第二步:本地部署
参考:ROS高效进阶第五章 — 机器人语音交互之ros集成科大讯飞中文语音库,实现语音控制机器人小车_科大讯飞ros机器人资料-CSDN博客安装环境:
unzip 下载的SDK sudo cp libs/x64/libmsc.so /usr/lib/ sudo apt update sudo apt install sox sudo apt install libsox-fmt-all
编译环境:
mkdir -p ~/YuYin/src cd ~/YuYin/src catkin_init_workspace cd ~/YuYin/ catkin_make source devel/setup.bash echo "source ~/YuYin/devel/setup.bash" >> ~/.bashrc source ~/.bashrc echo $ROS_PACKAGE_PATH
cd ~/YuYin/src catkin_create_pkg robot_voice roscpp rospy std_msgs geometry_msgs message_generation message_runtime cd robot_voice mkdir srv launch touch srv/StringToVoice.srv launch/voice_control_robot.launch touch src/voice_detector.cpp src/robot_controller.cpp src/voice_creator.cpp mkdir ifly_voice include/ifly_voice
将SDK分别移入相关目录,供编译使用:
目录如下:
voice_detector.cpp代码内容:
#include <ros/ros.h> #include <stdio.h> #include <signal.h> #include <stdlib.h> #include <string.h> #include <unistd.h> #include "ifly_voice/qisr.h" #include "ifly_voice/qtts.h" #include "ifly_voice/msp_cmn.h" #include "ifly_voice/formats.h" #include "ifly_voice/msp_errors.h" #include "ifly_voice/speech_recognizer.h" #include <std_msgs/String.h> #include <robot_voice/StringToVoice.h> class Helper { public: static void SignalHandler(int signal) { ROS_INFO("\nCaught signal %d. Exiting gracefully...\n", signal); exit(0); } }; class VoiceDetector { public: VoiceDetector() { ROS_INFO("VoiceDetector Constructor"); } ~VoiceDetector() { ROS_INFO("VoiceDetector Destructor"); } int Init() { int ret = MSP_SUCCESS; ret = MSPLogin(NULL, NULL, login_params_.c_str()); if (MSP_SUCCESS != ret) { ROS_ERROR("MSPLogin failed , Error code %d", ret); MSPLogout(); // Logout... return -1; } ROS_INFO("VoiceDetector MSP Login for update, waiting for seconds..."); return 0; } static void JoinTxt(const char *result, char is_last) { if (result) { std::string slice_txt = result; VoiceDetector::voice_txt_ += slice_txt; } if (is_last) { printf("voice txt : %s\n", VoiceDetector::voice_txt_.c_str()); } } static void InitSpeech() { VoiceDetector::voice_txt_ = ""; printf("clear cache, start Listening...\n"); } static void EndSpeech(int reason) { if (reason == END_REASON_VAD_DETECT) { printf("\nSpeaking done \n"); } else { printf("\nRecognizer error %d\n", reason); } } int SpeechOnce() { int ret; int i = 0; struct speech_rec iat; struct speech_rec_notifier recnotifier = { JoinTxt, InitSpeech, EndSpeech }; ret = sr_init(&iat, session_begin_params_.c_str(), SR_MIC, &recnotifier); if (ret) { ROS_ERROR("speech recognizer init failed"); return -1; } ret = sr_start_listening(&iat); if (ret) { printf("start listen failed %d\n", ret); } /* demo 15 seconds recording */ sleep(10); ret = sr_stop_listening(&iat); if (ret) { printf("stop listening failed %d\n", ret); } sr_uninit(&iat); return 0; } static std::string get_voice_txt_() { return voice_txt_; } private: const std::string login_params_ = "appid = d3b78914, work_dir = ."; const std::string session_begin_params_ = "sub = iat, domain = iat, language = zh_cn, " "accent = mandarin, sample_rate = 16000, " "result_type = plain, result_encoding = utf8"; const uint32_t BufferSize = 4096; uint64_t g_buffersize = BufferSize; static std::string voice_txt_; }; std::string VoiceDetector::voice_txt_ = ""; int main(int argc, char* argv[]) { int ret = 0; ros::init(argc, argv, "voice_detector"); ros::NodeHandle nh; // 创建 human_chatter 服务client ros::ServiceClient client_ = nh.serviceClient<robot_voice::StringToVoice>("human_chatter"); if (signal(SIGINT, Helper::SignalHandler) == SIG_ERR) { return -1; } VoiceDetector vd; ret = vd.Init(); if (ret < 0) { return -1; } while (1) { // 一次聆听 ret = vd.SpeechOnce(); if (ret < 0) { return -1; } // 获取当次聆听得到的内容 std::string voice_txt = VoiceDetector::get_voice_txt_(); if (voice_txt == "") { printf("voice_txt is empty, do not send chatter\n"); continue; } else if (voice_txt.find("结束") != std::string::npos) { break; } // 通过 human_chatter 服务,发给robot_controller,处理成功后,进入下一轮 robot_voice::StringToVoice::Request req; robot_voice::StringToVoice::Response resp; req.data = voice_txt; bool ok = client_.call(req, resp); if (ok) { printf("send human_chatter service success: %s\n", req.data.c_str()); } else { printf("failed to send human_chatter service\n"); } } ros::spin(); return 0; }
robot_controller.cpp代码内容:
#include <stdio.h> #include <signal.h> #include <stdlib.h> #include <string.h> #include <unistd.h> #include <ros/ros.h> #include <std_msgs/String.h> #include <geometry_msgs/Twist.h> #include <robot_voice/StringToVoice.h> class RobotController { public: RobotController() { ROS_INFO("RobotController Constructor"); } ~RobotController() { ROS_INFO("RobotController Destructor"); } int Init(ros::NodeHandle& nh) { cmd_pub_ = nh.advertise<geometry_msgs::Twist>("/cmd_vel", 1000); client_ = nh.serviceClient<robot_voice::StringToVoice>("str2voice"); return 0; } void ToDownstream(const std::string& answer_txt, float linear_x, float angular_z) { // 通过 str2voice 服务和 /cmd_vel topic向下游 voice_creator 和 mbot_gazebo 发送 robot_voice::StringToVoice::Request req; robot_voice::StringToVoice::Response resp; req.data = answer_txt; bool ok = client_.call(req, resp); if (ok) { printf("send str2voice service success: %s, and pub cmd_vel\n", req.data.c_str()); geometry_msgs::Twist msg; msg.linear.x = linear_x; msg.angular.z = angular_z; cmd_pub_.publish(msg); } else { ROS_ERROR("failed to send str2voice service"); } } bool ChatterCallbback(robot_voice::StringToVoice::Request &req, robot_voice::StringToVoice::Response &resp) { printf("i received: %s\n", req.data.c_str()); std::string voice_txt = req.data; // 根据指令关键字,发送对应的语音播包文字和 cmd_vel 命令 if (voice_txt.find("前") != std::string::npos) { ToDownstream("小车请向前跑", 0.3, 0); } else if (voice_txt.find("后") != std::string::npos) { ToDownstream("小车请向后倒", -0.3, 0); } else if (voice_txt.find("左") != std::string::npos) { ToDownstream("小车请向左转", 0, 0.3); } else if (voice_txt.find("右") != std::string::npos) { ToDownstream("小车请向右转", 0, -0.3); } else if (voice_txt.find("转") != std::string::npos) { ToDownstream("小车请打转", 0.3, -0.3); } resp.success = true; return resp.success; } void Start(ros::NodeHandle& nh) { // 申明 human_chatter 服务,ChatterCallbback是回调函数 chatter_server_ = nh.advertiseService("human_chatter", &RobotController::ChatterCallbback, this); } private: ros::ServiceServer chatter_server_; ros::Publisher cmd_pub_; ros::ServiceClient client_; }; int main(int argc, char* argv[]) { int ret = 0; ros::init(argc, argv, "voice_controller"); ros::NodeHandle nh; RobotController rc; rc.Init(nh); printf("this is a voice controller app for robot, you can say: 向前, 向后, 向左, 向右, 转圈, 结束\n"); rc.Start(nh); ros::spin(); return 0; }
voice_creator.cpp代码内容:
#include <ros/ros.h> #include <stdio.h> #include <signal.h> #include <stdlib.h> #include <string.h> #include <unistd.h> #include "ifly_voice/qisr.h" #include "ifly_voice/qtts.h" #include "ifly_voice/msp_cmn.h" #include "ifly_voice/formats.h" #include "ifly_voice/msp_errors.h" #include "ifly_voice/speech_recognizer.h" #include <robot_voice/StringToVoice.h> class Helper { public: static void SignalHandler(int signal) { ROS_INFO("\nCaught signal %d. Exiting gracefully...\n", signal); exit(0); } }; class VoiceCreator { public: VoiceCreator() { ROS_INFO("VoiceCreator Constructor"); } ~VoiceCreator() { ROS_INFO("VoiceCreator Destructor "); } int Init() { int ret = MSP_SUCCESS; ret = MSPLogin(NULL, NULL, login_params_.c_str()); if (MSP_SUCCESS != ret) { ROS_ERROR("MSPLogin failed , Error code %d", ret); MSPLogout(); // Logout... return -1; } ROS_INFO("VoiceCreator MSP Login for update, waiting for seconds..."); return 0; } int ProcessTxt(std::string& txt) { int ret = -1; FILE* fp = NULL; const char* sessionID = NULL; unsigned int audio_len = 0; int synth_status = MSP_TTS_FLAG_STILL_HAVE_DATA; WavePcmHdr_t 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 }; const char* src_text = txt.c_str(); const char* des_path = filename_.c_str(); const char* params = session_begin_params_.c_str(); if (NULL == src_text || NULL == des_path) { ROS_ERROR("params is error!"); return ret; } fp = fopen(des_path, "wb"); if (NULL == fp) { ROS_ERROR("open %s error", des_path); return ret; } /* 开始合成 */ sessionID = QTTSSessionBegin(params, &ret); if (MSP_SUCCESS != ret) { ROS_ERROR("QTTSSessionBegin failed, error code: %d", ret); fclose(fp); return ret; } ret = QTTSTextPut(sessionID, src_text, (unsigned int)strlen(src_text), NULL); if (MSP_SUCCESS != ret) { ROS_ERROR("QTTSTextPut failed, error code: %d",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) { ROS_ERROR("QTTSAudioGet failed, error code: %d",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) { ROS_ERROR("QTTSSessionEnd failed, error code: %d", ret); return ret; } // 播放语音文件 fp = popen(play_cmd_.c_str(),"r"); if (fp == NULL) { ROS_ERROR("play /tmp/tts_sample.wav failed"); return -1; } sleep(1); pclose(fp); return 0; } bool Speeking(robot_voice::StringToVoice::Request &req, robot_voice::StringToVoice::Response &resp) { int ret = -1; ret = ProcessTxt(req.data); if (MSP_SUCCESS != ret) { ROS_ERROR("AnswerVoice failed, error code: %d", ret); resp.success = false; return false; } else { resp.success = true; } return resp.success; } void Start(ros::NodeHandle& nh) { // 申明 str2voice 服务 server_ = nh.advertiseService("str2voice", &VoiceCreator::Speeking, this); } private: ros::ServiceServer server_; const std::string login_params_ = "appid = d3b78914, work_dir = ."; const std::string session_begin_params_ = "voice_name = xiaoyan, text_encoding = utf8, " "sample_rate = 16000, speed = 50, volume = 50, " "pitch = 50, rdn = 2"; //合成的语音文件名称 const std::string filename_ = "/tmp/tts_sample.wav"; //语音播放命令 const std::string play_cmd_ = "play /tmp/tts_sample.wav"; /* wav音频头部格式 */ typedef struct WavePcmHdr { 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 } WavePcmHdr_t; }; int main(int argc, char argv) { int ret = 0; ros::init(argc, argv, "voice_creator"); ros::NodeHandle nh; if (signal(SIGINT, Helper::SignalHandler) == SIG_ERR) { return -1; } VoiceCreator vc; ret = vc.Init(); if (ret < 0) { return -1; } vc.Start(nh); ros::spin(); return 0; }
StringToVoice.srv内容:
string data --- bool success
voice_control_robot.launch内容:
<launch> <node pkg="robot_voice" type="voice_creator" name="voice_creator" output="screen" /> <node pkg="robot_voice" type="robot_controller" name="robot_controller" output="screen" /> <node pkg="robot_voice" type="voice_detector" name="voice_detector" launch-prefix="bash -c 'sleep 5; $0 $@'" output="screen" /> </launch>
CMakeLists.txt内容:
cmake_minimum_required(VERSION 3.0.2) project(robot_voice) add_compile_options(-std=c++11) find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs geometry_msgs message_generation ) add_service_files( FILES StringToVoice.srv ) generate_messages( DEPENDENCIES std_msgs ) catkin_package( CATKIN_DEPENDS message_runtime roscpp rospy std_msgs ) include_directories( include ${catkin_INCLUDE_DIRS} ) add_executable(voice_detector src/voice_detector.cpp ifly_voice/speech_recognizer.c ifly_voice/linuxrec.c) add_executable(robot_controller src/robot_controller.cpp) add_executable(voice_creator src/voice_creator.cpp) add_dependencies(voice_detector ${PROJECT_NAME}_generate_messages_cpp) target_link_libraries(voice_detector ${catkin_LIBRARIES} libmsc.so -ldl -lpthread -lm -lrt -lasound ) add_dependencies(robot_controller ${PROJECT_NAME}_generate_messages_cpp) target_link_libraries(robot_controller ${catkin_LIBRARIES} ) add_dependencies(voice_creator ${PROJECT_NAME}_generate_messages_cpp) target_link_libraries(voice_creator ${catkin_LIBRARIES} libmsc.so -ldl -pthread )
编译并运行:
cd ~/YuYin/ catkin_make -DCATKIN_WHITELIST_PACKAGES="robot_voice;mbot_gazebo" source devel/setup.bash roslaunch mbot_gazebo view_mbot_gazebo.launch // 再开一个窗口 source devel/setup.bash roslaunch robot_voice voice_control_robot.launch
免责声明:本站所有文章内容,图片,视频等均是来源于用户投稿和互联网及文摘转载整编而成,不代表本站观点,不承担相关法律责任。其著作权各归其原作者或其出版社所有。如发现本站有涉嫌抄袭侵权/违法违规的内容,侵犯到您的权益,请在线联系站长,一经查实,本站将立刻删除。 本文来自网络,若有侵权,请联系删除,如若转载,请注明出处:https://haidsoft.com/132579.html