2 #include <geometry_msgs/Twist.h> 3 #include <std_msgs/Bool.h> 4 #include <std_msgs/Empty.h> 5 #include <std_msgs/String.h> 29 std::string(
"~/catkin_ws/src/xbot_talker/cache/grammar_config"));
31 std::string(
"~/catkin_ws/src/xbot_talker/defaultconfig/audio/nihao_test.pcm"));
33 std::string(
"~/catkin_ws/src/xbot_talker/cache/audio"));
50 "accent = mandarin, sample_rate = 16000, " 51 "result_type = plain, result_encoding = utf8";
64 ROS_INFO_STREAM(
"--------Speech recognition module is ready to be waken up!--------");
92 xbot_talker::keyword_config::Response& res)
94 if (req.keyword !=
"")
112 xbot_talker::recog_result recog_result;
113 recog_result.recog_result = result;
114 recog_result.recog_accuracy = accuracy;
121 xbot_talker::online_asr_result recog_result;
122 recog_result.online_asr_result = result;
167 char* recog_result = NULL;
185 if (recog_result == NULL)
196 std::ofstream result_log(
log_path +
"/asr_online_recog_result_log.txt", std::ios::app);
197 if (result_log.is_open())
221 struct DataBuff pcm_buff = { NULL, 0 };
226 char* recog_result_online;
237 std::ofstream result_log(
log_path +
"/asr_online_recog_result_log.txt", std::ios::app);
238 if (result_log.is_open())
248 ROS_INFO_STREAM(
"Online asr result is :" << recog_result_online << std::endl);
256 std::string dialogue_prompt_wav =
"play " +
base_path +
"/defaultconfig/audio/call.wav";
257 system(dialogue_prompt_wav.c_str());
267 offlineThread.join();
299 res.chat_success =
true;
312 std::string dialogue_prompt_wav =
"play " +
base_path +
"/defaultconfig/audio/call.wav";
313 system(dialogue_prompt_wav.c_str());
314 std_msgs::Bool enable_sound;
323 offlineThread.join();
324 onlineThreadBaidu.join();
372 nlp_nodehandle.param(
"/nlp_sample/base_path",
base_path, std::string(
"~/catkin_ws/src/xbot_talker"));
373 nlp_nodehandle.param(
"/nlp_sample/nlp_config_path", nlp_config_path,
374 std::string(
"~/catkin_ws/src/xbot_talker/defaultconfig/answer_dic.csv"));
376 nlp_nodehandle.param(
"/nlp_sample/log_path",
log_path, std::string(
"~/catkin_ws/src/xbot_talker/cache/log"));
381 for (
int i = 0; i < 2; i++)
383 pubStartAwaken(
true);
386 ROS_INFO_STREAM(
"--------Result feedback module is ready to start!--------");
389 result_handle.readAnswerTable(nlp_config_path);
394 start_recog_pub = nlp_nodehandle.advertise<xbot_talker::awaken_status>(
"xbot_talker/awaken_status", 100);
395 start_awaken_pub = nlp_nodehandle.advertise<std_msgs::Bool>(
"xbot_talker/enable_awake", 100);
396 mov_control_pub = nlp_nodehandle.advertise<geometry_msgs::Twist>(
"/cmd_vel_mux/input/teleop", 1000);
397 left_get_pub = nlp_nodehandle.advertise<std_msgs::Empty>(
"/arm/commands/left_get", 10);
398 right_get_pub = nlp_nodehandle.advertise<std_msgs::Empty>(
"/arm/commands/right_get", 10);
400 left_put_pub = nlp_nodehandle.advertise<std_msgs::Empty>(
"/arm/commands/left_put", 10);
401 right_put_pub = nlp_nodehandle.advertise<std_msgs::Empty>(
"/arm/commands/right_put", 10);
403 left_grip_pub = nlp_nodehandle.advertise<std_msgs::Bool>(
"/arm/commands/left_grip", 10);
404 right_grip_pub = nlp_nodehandle.advertise<std_msgs::Bool>(
"/arm/commands/right_grip", 10);
405 welcome_yes_pub = nlp_nodehandle.advertise<std_msgs::Bool>(
"/welcome/yes", 10);
406 welcome_kp_pub = nlp_nodehandle.advertise<std_msgs::String>(
"/welcome/kp", 10);
411 recog_result_sub = nlp_nodehandle.subscribe(std::string(
"xbot_talker/recog_result"), 10,
413 online_result_sub = nlp_nodehandle.subscribe(std::string(
"/xbot_talker/online_recog_result"), 10,
419 dialog_config_service = nlp_nodehandle.advertiseService(std::string(
"/xbot_talker/nlp_dialog_config"),
424 xbot_talker::nlpdialog_config::Response& res)
426 if (req.keyword !=
"back_config")
428 bool is_repeate = result_handle.isKeywordRepeated(req.keyword);
429 if (is_repeate ==
false)
432 std::vector<std::string> dialog_add;
433 dialog_add.push_back(req.keyword);
434 dialog_add.push_back(req.answer);
435 dialog_add.push_back(std::to_string(req.action));
436 dialog_add.push_back(std::to_string(req.action_mode));
439 result_handle.readAnswerTable(nlp_config_path);
452 result_handle.readAnswerTable(nlp_config_path);
459 xbot_talker::awaken_status awaken_status;
460 awaken_status.is_awaken = is_awaken;
461 start_recog_pub.publish(awaken_status);
466 std_msgs::Bool enable_awaken;
467 enable_awaken.data = enable_awake;
468 start_awaken_pub.publish(enable_awaken);
474 std_msgs::Empty empty_msg;
475 std_msgs::Bool bool_msg;
476 switch (robot_action)
479 left_get_pub.publish(empty_msg);
482 left_put_pub.publish(empty_msg);
485 right_get_pub.publish(empty_msg);
488 right_put_pub.publish(empty_msg);
491 bool_msg.data =
true;
492 left_grip_pub.publish(bool_msg);
495 bool_msg.data =
false;
496 left_grip_pub.publish(bool_msg);
499 bool_msg.data =
true;
500 right_grip_pub.publish(bool_msg);
503 bool_msg.data =
false;
504 right_grip_pub.publish(bool_msg);
512 msg.data = enable_welcome;
513 welcome_yes_pub.publish(msg);
518 std_msgs::String msg;
520 welcome_kp_pub.publish(msg);
526 geometry_msgs::Twist twist;
533 switch (robot_action)
536 twist.linear.x = 0.15;
537 mov_control_pub.publish(twist);
541 twist.linear.x = -0.15;
542 mov_control_pub.publish(twist);
546 twist.angular.z = 0.78;
547 mov_control_pub.publish(twist);
551 twist.angular.z = -0.78;
552 mov_control_pub.publish(twist);
559 ROS_INFO_STREAM(
"recog_result is :" << msg.recog_result <<
" |recog_accuracy is :" << msg.recog_accuracy
562 std::ofstream result_log(
log_path +
"/recog_result_log.txt", std::ios::app);
563 if (result_log.is_open())
565 result_log <<
log_count_ <<
":" << msg.recog_result << std::endl;
574 bool ret = result_handle.resultIsValid(msg.recog_result);
578 std::string sorry_prompt_wav =
"play " +
base_path +
"/defaultconfig/audio/none_speech.wav";
579 system(sorry_prompt_wav.c_str());
581 pubStartAwaken(
true);
584 else if (msg.recog_accuracy < 15)
588 std::string sorry_prompt_wav =
"play " +
base_path +
"/defaultconfig/audio/dontknow.wav";
589 system(sorry_prompt_wav.c_str());
591 pubStartAwaken(
true);
592 pubStartRecog(
true,
true);
594 else if (msg.recog_accuracy < 35)
598 std::string sorry_prompt_wav =
"play " +
base_path +
"/defaultconfig/audio/low_SC.wav";
599 system(sorry_prompt_wav.c_str());
602 pubStartRecog(
true,
true);
606 pubStartRecog(
true,
false);
612 result_handle.keywordDetection();
614 result_handle.keywordResponse(
base_path +
"/cache/wav");
617 int robot_action = result_handle.actionDetect();
621 pubStartRecog(
true,
true);
623 else if ((robot_action >= 3) && (robot_action <= 14))
625 if (robot_action < 7)
627 pubMoveControl(robot_action);
630 else if (robot_action >= 7)
632 pubArmControl(robot_action);
637 pubStartRecog(
true,
true);
642 pubStartRecog(
true,
true);
648 pubStartRecog(
false,
false);
650 ROS_INFO_STREAM(
"--If you want to start asr module, say the awaken_word again! --");
657 pubWelcomeKp(
"kp_origin");
658 pubStartRecog(
false,
false);
659 pubStartAwaken(
true);
665 pubWelcomeKp(
"kp_fangyang");
666 pubStartRecog(
true,
false);
673 pubWelcomeKp(
"kp_cxm");
674 pubStartRecog(
true,
false);
683 pubStartRecog(
true,
true);
687 pubStartAwaken(
true);
691 result_handle.uninitNLP();
696 tuling_answer_text_ =
"";
697 ROS_INFO_STREAM(
"online asr result is :" << msg.online_asr_result << std::endl);
698 std::ofstream result_log(
log_path +
"/recog_result_log.txt", std::ios::app);
699 if (result_log.is_open())
701 result_log <<
log_count_ <<
":" << msg.online_asr_result << std::endl;
711 bool ret = result_handle.resultIsValid(msg.online_asr_result);
715 std::string sorry_prompt_wav =
"play " +
base_path +
"/defaultconfig/audio/none_speech.wav";
716 system(sorry_prompt_wav.c_str());
717 pubStartAwaken(
true);
718 pubStartRecog(
true,
true);
724 tuling_robot.setAskJson(msg.online_asr_result);
726 tuling_robot.callTulingApi();
728 tuling_answer_text_ = tuling_robot.textFromJson();
729 ROS_INFO_STREAM(
"TuLing robot answer is:" << tuling_answer_text_ << std::endl);
731 tuling_robot.uninitTuling();
732 result_handle.resultIsValid(tuling_answer_text_);
733 bool has_answer = result_handle.keywordDetection();
735 if (has_answer ==
true)
738 result_handle.keywordResponse(
base_path +
"/cache/wav");
741 int robot_action = result_handle.actionDetect();
745 pubStartRecog(
true,
true);
747 else if ((robot_action >= 3) && (robot_action <= 14))
749 if (robot_action < 7)
751 pubMoveControl(robot_action);
754 else if (robot_action >= 7)
756 pubArmControl(robot_action);
761 pubStartRecog(
true,
true);
765 pubStartAwaken(
true);
770 pubStartRecog(
false,
false);
772 ROS_INFO_STREAM(
"--If you want to start asr module, say the awaken_word again! --");
773 pubStartAwaken(
true);
779 pubWelcomeKp(
"kp_origin");
780 pubStartRecog(
false,
false);
781 pubStartAwaken(
true);
787 pubWelcomeKp(
"kp_fangyang");
788 pubStartRecog(
false,
false);
789 pubStartAwaken(
true);
795 pubWelcomeKp(
"kp_cxm");
796 pubStartRecog(
true,
false);
797 pubStartAwaken(
true);
805 pubStartRecog(
true,
true);
809 pubStartAwaken(
true);
810 pubStartRecog(
true,
true);
821 pubStartRecog(
true,
true);
825 pubStartAwaken(
true);
829 result_handle.uninitNLP();
847 awaken_nodehandle.param(
"/awaken_sample/awaken_mode", awaken_mode, std::string(
"mic"));
848 awaken_nodehandle.param(
"/awaken_sample/base_path",
base_path, std::string(
"~/catkin_ws/src/xbot_talker"));
849 awaken_nodehandle.param(
"/awaken_sample/pcm_file",
pcm_file,
850 std::string(
"~/catkin_ws/src/xbot_talker/defaultconfig/audio/awaken.pcm"));
851 awaken_nodehandle.param(
"/awaken_sample/enable_record_save",
enable_record_save,
bool(
true));
853 awaken_nodehandle.param(
"/awaken_sample/audio_save_path",
audio_save_path,
854 std::string(
"~/catkin_ws/src/xbot_talker/cache/"));
855 awaken_nodehandle.param(
"/awaken_sample/log_path",
log_path, std::string(
"~/catkin_ws/src/xbot_talker/cache/"));
857 awaken_nodehandle.param(
"/awaken_sample/audio_channel",
audio_channel,
int(1));
858 awaken_nodehandle.param(
"/awaken_sample/record_time",
record_time,
int(60));
862 ROS_INFO_STREAM(
"--------Voice wake up module is ready to be waken up!--------");
867 is_awaken_pub = awaken_nodehandle.advertise<xbot_talker::awaken_status>(
"xbot_talker/awaken_status", 100);
872 start_awaken_sub = awaken_nodehandle.subscribe(std::string(
"xbot_talker/enable_awake"), 10,
878 xbot_talker::awaken_status awaken_status;
879 awaken_status.is_awaken = is_awaken;
880 is_awaken_pub.publish(awaken_status);
887 if (awaken_module.is_awaken)
889 if (awaken_mode ==
"mic")
891 awaken_module.stopRecordThroughMIC();
895 awaken_module.saveRecordDataToFile();
898 std::string dialogue_prompt_wav =
"play " +
base_path +
"/defaultconfig/audio/wozai.wav";
899 system(dialogue_prompt_wav.c_str());
902 awaken_module.is_awaken =
false;
914 if (msg->data ==
true)
917 awaken_module.awakenInit();
918 if (awaken_mode ==
"file")
920 awaken_module.getPcmFileData();
921 awaken_module.dataLoopAwaken();
930 awaken_module.uninitAsr();
949 tts_nodehandle.param(
"/tts_sample/base_path",
base_path, std::string(
"~/catkin_ws/src/xbot_talker"));
951 std::string(
"~/catkin_ws/src/xbot_talker/cache/audio"));
952 tts_nodehandle.param(
"/tts_sample/log_path",
log_path, std::string(
"~/catkin_ws/src/xbot_talker/cache/log"));
954 tts_nodehandle.param(
"/tts_sample/audio_channel",
audio_channel,
int(1));
960 ROS_INFO_STREAM(
"--------TextToSpeech module is ready to start.--------");
972 std::string audiofile = req.audio_path;
973 std::string dialogue_prompt_wav =
"play " + audiofile;
974 system(dialogue_prompt_wav.c_str());
977 ROS_INFO(
"----------start to request the tts service-----------");
980 string text = req.tts_text;
991 tts_client = tts_nodehandle.serviceClient<xbot_talker::xbot_tts>(std::string(
"xbot/xbot_tts"));
999 ROS_INFO(
"----------start to request the tts service-----------");
1002 string text = req.tts_text;
void pubOfflineRecogResult(const std::string result, const int accuracy)
void pubStartRecog(bool is_awaken, bool enable_chat)
void pubMoveControl(const int robot_action)
void pubWelcomeYes(bool enable_welcome)
ros::Publisher recog_result_pub
void publish(const boost::shared_ptr< M > &message) const
XfeiSpeechRecog xfei_sr_online
bool requestKeywordConfig(xbot_talker::keyword_config::Request &req, xbot_talker::keyword_config::Response &res)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void subscribeOfflineRecogResult(const xbot_talker::recog_result)
void initAsr()
科大讯飞识别模块的初始化.
static CommonConfig & get_instance()
XfeiSpeechRecog xfei_sr_offline
void initAndConfigAsr()
百度语音识别模块的初始化,设置asr相关参数.
void pubStartAwaken(bool enable_awake)
void uninitAsr()
一次识别结束后释放资源.
ros::Subscriber is_awaken_sub
std::string audio_save_path
std::string baidu_online_result
FileOperation config_file
void loginToXunfei(const std::string base_path)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
科大讯飞语音识别模块接口头文件. TODO: 还需要添加版权、版本等信息
ros::NodeHandle asr_nodehandle
bool playCallback(xbot_talker::play::Request &req, xbot_talker::play::Response &res)
bool ttsCallback(xbot_talker::xbot_tts::Request &req, xbot_talker::xbot_tts::Response &res)
void subscribeAwakenStatus(const xbot_talker::awaken_status)
std::string readFileAsString(const std::string file_path)
void setAsrParams(const std::string base_path, const std::string pcm_file, const int channel)
设置语音模块需外部传入的路径等参数.
std::vector< std::string > offline_result_vector
std::string offline_recog_result
void uninitAsr()
一次识别结束后释放资源.
char * dataLoopRecog()
将全部音频数据循环写入科大讯飞接口进行识别并获取完整的json识别结果.
void pubStartRecog(bool is_awaken)
std::string resultFromJson()
从完整的json语音识别结果中解析出需要的字符串结果.
struct DataBuff recordThroughMIC(const float record_time, bool enable_audio_save)
录音接口.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::Publisher online_result_pub
void pubArmControl(const int robot_action)
bool requestChat(xbot_talker::chat::Request &req, xbot_talker::chat::Response &res)
void setAsrParams(const std::string base_path, const std::string pcm_file, const std::string params, const int channel)
设置语音模块需外部传入的路径等参数.
ros::ServiceServer keyword_config_service
char * runAsrAndRecog()
将pcm_data_结构体里存储的音频用于百度在线语音识别并获取识别结果.
bool audioConverter(const std::string base_path, const char *src_text)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceServer chat_server_
void speechGetToken()
获取百度在线语音识别的Token.
std::string xfei_online_result
void pubWelcomeKp(const std::string kp_name)
struct DataBuff recordThroughMIC(const float record_time, bool enable_audio_save)
录音接口.
void subscribeStartAwaken(const std_msgs::BoolConstPtr)
#define ROS_INFO_STREAM(args)
std::string configGramParas(const std::string base_path, const std::string grammar_file)
std::string xunfei_online_asr_params_
void subscribeOnlineRecogResult(const xbot_talker::online_asr_result)
void writeRowData(std::string csv_file, std::vector< std::string > row_vector)
#define ROS_ERROR_STREAM(args)
BaiduAsrOnline baidu_sr_online
void getPcmFileData()
读取pcm文件里的音频数据,并将数据的内容和数据大小存入pcm_data_结构体.
std::vector< std::string > resultFromJson()
从完整的json语音识别结果中解析出需要的字符串结果和置信度值.
void getPcmFileData()
读取pcm文件里的音频数据,并将数据的内容和数据大小存入pcm_data_.
bool requestDialogConfig(xbot_talker::nlpdialog_config::Request &req, xbot_talker::nlpdialog_config::Response &res)
void pubOnlineRecogResult(const std::string result)
void getPCMData(struct DataBuff pcm_buff)
获取pcm数据接口.
void getPCMData(struct DataBuff pcm_buff)
获取pcm数据接口.