xbot_talker_ros.cpp
Go to the documentation of this file.
1 #include "ros/xbot_talker_ros.h"
2 #include <geometry_msgs/Twist.h>
3 #include <std_msgs/Bool.h>
4 #include <std_msgs/Empty.h>
5 #include <std_msgs/String.h>
6 #include <thread>
7 #include "common_config.h"
9 /**************************************************
10 ************* Ros ASR Module *******************
11 ***************************************************/
12 
14 {
18  // 获取参数
19  asr_nodehandle.param("/asr_sample/enable_xfei_online", enable_xfei_online, bool(false));
20  asr_nodehandle.param("/asr_sample/enable_baidu_online", enable_baidu_online, bool(false));
21  asr_nodehandle.param("/asr_sample/enable_offline", enable_offline, bool(true));
22 
23  asr_nodehandle.param("/asr_sample/use_pcm_file", use_pcm_file, bool(false));
24  asr_nodehandle.param("/asr_sample/use_mic", use_mic, bool(true));
25  asr_nodehandle.param("/asr_sample/enable_record_save", enable_record_save, bool(true));
26 
27  asr_nodehandle.param("/asr_sample/base_path", base_path, std::string("~/catkin_ws/src/xbot_talker"));
28  asr_nodehandle.param("/asr_sample/grammar_path", grammar_path,
29  std::string("~/catkin_ws/src/xbot_talker/cache/grammar_config"));
30  asr_nodehandle.param("/asr_sample/pcm_file", pcm_file,
31  std::string("~/catkin_ws/src/xbot_talker/defaultconfig/audio/nihao_test.pcm"));
32  asr_nodehandle.param("/asr_sample/audio_save_path", audio_save_path,
33  std::string("~/catkin_ws/src/xbot_talker/cache/audio"));
34  asr_nodehandle.param("/asr_sample/log_path", log_path, std::string("~/catkin_ws/src/xbot_talker/cache/log"));
35 
36  asr_nodehandle.param("/asr_sample/audio_channel", audio_channel, int(1));
37  asr_nodehandle.param("/asr_sample/record_time", record_time, float(5));
38  // 科大讯飞asr登录以及语法参数配置
39  CommonConfig& xunfei_config = CommonConfig::get_instance();
40  xunfei_config.loginToXunfei(base_path);
41  if (enable_offline == true)
42  {
45  }
46  // 设置科大讯飞在线语音识别相关参数
47  if (enable_xfei_online == true)
48  {
49  xunfei_online_asr_params_ = "sub = iat, domain = iat, language = zh_cn, "
50  "accent = mandarin, sample_rate = 16000, "
51  "result_type = plain, result_encoding = utf8";
53  }
54  if (enable_baidu_online == true)
55  {
56  // 设置百度在线语音识别相关参数
58  // 百度语音识别模块的初始化,设置asr相关参数
60  // 获取百度在线语音识别的Token
62  }
63 
64  ROS_INFO_STREAM("--------Speech recognition module is ready to be waken up!--------");
65 }
66 
67 // 发布的话题
69 {
70  recog_result_pub = asr_nodehandle.advertise<xbot_talker::recog_result>("xbot_talker/recog_result", 100);
71  online_result_pub = asr_nodehandle.advertise<xbot_talker::online_asr_result>("xbot_talker/online_recog_result", 100);
72  //sound_mute = asr_nodehandle.advertise<std_msgs::Bool>("mobile_base/commands/sound_enable", 100);
73 }
74 
75 // 订阅的话题
77 {
78  is_awaken_sub = asr_nodehandle.subscribe(std::string("xbot_talker/awaken_status"), 10,
80 }
81 
83 {
84  keyword_config_service = asr_nodehandle.advertiseService(std::string("/xbot_talker/asr_keyword_config"),
86  chat_server_ = asr_nodehandle.advertiseService(std::string("/xbot/chat"),
88 }
89 
90 // 添加新的关键词构建语法后,重新配置语法参数
91 bool ASRModuleRos::requestKeywordConfig(xbot_talker::keyword_config::Request& req,
92  xbot_talker::keyword_config::Response& res)
93 {
94  if (req.keyword != "")
95  {
96  std::string bnf_word;
97  bnf_word = config_file.readFileAsString(base_path + "/userconfig/grammar.bnf");
98  ROS_INFO_STREAM("BNF file :" << bnf_word);
99  CommonConfig& xunfei_config = CommonConfig::get_instance();
101  res.error_code = 0;
102  }
103  else
104  {
105  res.error_code = 1;
106  }
107 }
108 
109 // 识别结果的发布.
110 void ASRModuleRos::pubOfflineRecogResult(const std::string result, const int accuracy)
111 {
112  xbot_talker::recog_result recog_result;
113  recog_result.recog_result = result;
114  recog_result.recog_accuracy = accuracy;
115  recog_result_pub.publish(recog_result);
116 }
117 
118 // 完整的百度在线语音识别结果的发布.
119 void ASRModuleRos::pubOnlineRecogResult(const std::string result)
120 {
121  xbot_talker::online_asr_result recog_result;
122  recog_result.online_asr_result = result;
123  online_result_pub.publish(recog_result);
124 }
125 
126 // 科大讯飞离线语音识别线程
128 {
129  recog_result_json = NULL;
130  if (enable_offline == true)
131  {
132  if (use_pcm_file == true)
133  {
135  }
136  else if (use_mic == true)
137  {
138  // 固定时长录音
141  }
142  // 科大讯飞识别模块的初始化
144  // 将全部音频数据循环写入科大讯飞接口进行识别并获取完整的json识别结果
146 
147  if (recog_result_json == NULL)
148  {
149  offline_result_vector[0] = "none_result";
150  offline_result_vector[1] = "0";
151  csv_file.writeRowData(log_path + "/asr_recog_result_log.csv", offline_result_vector);
152  }
153  else
154  {
155  // 在识别结果不为空时,从json结果中解析出需要的结果和置信度
157  csv_file.writeRowData(log_path + "/asr_recog_result_log.csv", offline_result_vector);
158  }
159  // 一次识别结束后释放资源
161  }
162 }
163 
164 // 科大讯飞在线语音识别线程
166 {
167  char* recog_result = NULL;
168  if (enable_xfei_online == true)
169  {
170  if (use_pcm_file == true)
171  {
172  // 获取pcm_file的数据
174  }
175  else if (use_mic == true)
176  {
177  ROS_INFO_STREAM("PCM" << pcm_buff.size << std::endl);
179  }
180  // 科大讯飞识别模块的初始化
182  // 将全部音频数据循环写入科大讯飞接口进行识别并获取完整的json识别结果
183  recog_result = xfei_sr_online.dataLoopRecog();
184  // 有时会出现离线识别结果置信度很低,但实际上无语音输入的情况,此情况下在线识别结果为空,需要加一个判断
185  if (recog_result == NULL)
186  {
187  xfei_online_result = "none_result";
188  }
189  else
190  {
191  xfei_online_result = recog_result;
192  }
193 
194  ROS_INFO_STREAM("Xunfei online iat result is :" << xfei_online_result << std::endl);
195 
196  std::ofstream result_log(log_path + "/asr_online_recog_result_log.txt", std::ios::app);
197  if (result_log.is_open())
198  {
199  result_log << online_log_count_ << ":" << xfei_online_result << std::endl;
201  }
202  else
203  {
204  ROS_ERROR_STREAM("LOG ERROR");
205  }
206  result_log.close();
208  }
209 }
210 // 百度在线语音识别线程
212 {
213  if (enable_baidu_online == true)
214  {
215  if (use_pcm_file == true)
216  { // 读取pcm文件里的音频数据
218  }
219  else if (use_mic == true)
220  {
221  struct DataBuff pcm_buff = { NULL, 0 };
222  // 录音
224  baidu_sr_online.getPCMData(pcm_buff);
225  }
226  char* recog_result_online;
227  // 百度在线语音识别并获取识别结果
228  recog_result_online = baidu_sr_online.runAsrAndRecog();
229  // 从完整的json语音识别结果中解析出需要的字符串结果
231  if (baidu_online_result.empty())
232  {
233  baidu_online_result = "none_result";
234  }
235  // 一次识别结束后释放资源
237  std::ofstream result_log(log_path + "/asr_online_recog_result_log.txt", std::ios::app);
238  if (result_log.is_open())
239  {
240  result_log << online_log_count_ << ":" << recog_result_online << std::endl;
242  }
243  else
244  {
245  ROS_ERROR_STREAM("LOG ERROR");
246  }
247  result_log.close();
248  ROS_INFO_STREAM("Online asr result is :" << recog_result_online << std::endl);
249  ROS_INFO_STREAM("Online asr finall result is :" << baidu_online_result << std::endl);
250  }
251 }
252 
253 bool ASRModuleRos::requestChat(xbot_talker::chat::Request &req, xbot_talker::chat::Response &res){
254  if(req.start_chat){
255  //播放“嘟”声提示音.
256  std::string dialogue_prompt_wav = "play " + base_path + "/defaultconfig/audio/call.wav";
257  system(dialogue_prompt_wav.c_str());
258  //std_msgs::Bool enable_sound;
259  //enable_sound.data = false;
260  //sound_mute.publish(enable_sound);
262  baidu_online_result = "";
263  xfei_online_result = "";
264  ROS_INFO_STREAM("--------Speech recognition is started!--------");
265  //std::thread onlineThreadBaidu(&ASRModuleRos::onlineRecogBaidu, this);
266  std::thread offlineThread(&ASRModuleRos::offlineRecog, this);
267  offlineThread.join();
268  //onlineThreadBaidu.join();
269  if (std::stoi(offline_result_vector[1]) >= 35)
270  {
271  // 科大讯飞离线识别结果准确度>=35时,默认为识别准确,直接发布离线识别结果,不再进行在线处理。
273  }
274  else if (enable_xfei_online == true && offline_result_vector[0] != "none_result")
275  {
276  // 如果离线准确度小于35,且离线结果不为空(离线结果为空意味着录音时间段内没有任何语音输入,十分安静),
277  // 并且讯飞在线识别功能开启的情况下,调用在线语音进行识别,发布在线识别结果。
278  onlineRecogXfei();
280  }
281  else if (enable_baidu_online == true && offline_result_vector[0] != "none_result")
282  {
283  // 同上。同等网络状况下,百度在线识别比科大讯飞在线识别慢很多,甚至因网络状况出现卡顿。
284  // 所以建议使用科大讯飞在线和离线结合的方式。
286  }
287  else
288  {
290  }
291  ROS_INFO_STREAM("Baidu online speech recog result: " << baidu_online_result << std::endl);
292  ROS_INFO_STREAM("Xunfei online speech recog result: " << xfei_online_result << std::endl);
293  ROS_INFO_STREAM("Xunfei offline speech recog result: " << offline_result_vector[0] << std::endl);
294  pcm_buff.data = NULL;
295  pcm_buff.size = 0;
296  //enable_sound.data = true;
297  //sound_mute.publish(enable_sound);
298  }
299  res.chat_success =true;
300  return true;
301 }
302 
303 
304 
305 // topic:"xbot_talker/awaken_status"的回调函数.
306 // 当is_awaken为true时,开启语法识别相关功能.
307 void ASRModuleRos::subscribeAwakenStatus(const xbot_talker::awaken_status msg)
308 {
309  if (msg.is_awaken)
310  {
311  //播放“嘟”声提示音.
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;
315  //enable_sound.data = false;
316  //sound_mute.publish(enable_sound);
318  baidu_online_result = "";
319  xfei_online_result = "";
320  ROS_INFO_STREAM("--------Speech recognition is awakened!--------");
321  std::thread onlineThreadBaidu(&ASRModuleRos::onlineRecogBaidu, this);
322  std::thread offlineThread(&ASRModuleRos::offlineRecog, this);
323  offlineThread.join();
324  onlineThreadBaidu.join();
325  if (std::stoi(offline_result_vector[1]) >= 35)
326  {
327  // 科大讯飞离线识别结果准确度>=35时,默认为识别准确,直接发布离线识别结果,不再进行在线处理。
329  }
330  else if (enable_xfei_online == true && offline_result_vector[0] != "none_result")
331  {
332  // 如果离线准确度小于35,且离线结果不为空(离线结果为空意味着录音时间段内没有任何语音输入,十分安静),
333  // 并且讯飞在线识别功能开启的情况下,调用在线语音进行识别,发布在线识别结果。
334  onlineRecogXfei();
336  }
337  else if (enable_baidu_online == true && offline_result_vector[0] != "none_result")
338  {
339  // 同上。同等网络状况下,百度在线识别比科大讯飞在线识别慢很多,甚至因网络状况出现卡顿。
340  // 所以建议使用科大讯飞在线和离线结合的方式。
342  }
343  else
344  {
346  }
347  ROS_INFO_STREAM("Baidu online speech recog result: " << baidu_online_result << std::endl);
348  ROS_INFO_STREAM("Xunfei online speech recog result: " << xfei_online_result << std::endl);
349  ROS_INFO_STREAM("Xunfei offline speech recog result: " << offline_result_vector[0] << std::endl);
350  pcm_buff.data = NULL;
351  pcm_buff.size = 0;
352  //enable_sound.data = true;
353  //sound_mute.publish(enable_sound);
354  }
355 }
356 
357 /**************************************************
358 ************* Ros NLP Module *******************
359 ***************************************************/
361 {
362 }
364 {
365 }
367 {
368  advertiseTopics();
369  subscribeTopics();
371  // 获取参数
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"));
375 
376  nlp_nodehandle.param("/nlp_sample/log_path", log_path, std::string("~/catkin_ws/src/xbot_talker/cache/log"));
377 
378  // 科大讯飞登录
379  CommonConfig& xunfei_config = CommonConfig::get_instance();
380  xunfei_config.loginToXunfei(base_path);
381  for (int i = 0; i < 2; i++)
382  {
383  pubStartAwaken(true);
384  sleep(1);
385  }
386  ROS_INFO_STREAM("--------Result feedback module is ready to start!--------");
387 
388  // 读取对话配置文件内容保存进answer_table变量
389  result_handle.readAnswerTable(nlp_config_path);
390 }
391 
393 {
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);
399 
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);
402 
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);
407 }
408 
410 {
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,
415 }
416 
418 {
419  dialog_config_service = nlp_nodehandle.advertiseService(std::string("/xbot_talker/nlp_dialog_config"),
421 }
422 
423 bool NLPModuleRos::requestDialogConfig(xbot_talker::nlpdialog_config::Request& req,
424  xbot_talker::nlpdialog_config::Response& res)
425 {
426  if (req.keyword != "back_config")
427  {
428  bool is_repeate = result_handle.isKeywordRepeated(req.keyword);
429  if (is_repeate == false)
430  {
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));
437  csv_file.writeRowData(nlp_config_path, dialog_add);
438  // 重新读取对话配置文件内容保存进answer_table变量
439  result_handle.readAnswerTable(nlp_config_path);
440  res.error_code = 0;
441  return true;
442  }
443  else
444  {
445  res.error_code = 1;
446  return false;
447  }
448  }
449  else
450  {
451  // 重新读取对话配置文件内容保存进answer_table变量
452  result_handle.readAnswerTable(nlp_config_path);
453  return true;
454  }
455 }
456 
457 void NLPModuleRos::pubStartRecog(bool is_awaken, bool enable_chat)
458 {
459  xbot_talker::awaken_status awaken_status;
460  awaken_status.is_awaken = is_awaken;
461  start_recog_pub.publish(awaken_status);
462 }
463 
464 void NLPModuleRos::pubStartAwaken(bool enable_awake)
465 {
466  std_msgs::Bool enable_awaken;
467  enable_awaken.data = enable_awake;
468  start_awaken_pub.publish(enable_awaken);
469 }
470 
471 // 控制机械臂动作
472 void NLPModuleRos::pubArmControl(const int robot_action)
473 {
474  std_msgs::Empty empty_msg;
475  std_msgs::Bool bool_msg;
476  switch (robot_action)
477  {
478  case RAISE_LEFT_HAND:
479  left_get_pub.publish(empty_msg);
480  break;
481  case PUT_DOWM_LEFT_HAND:
482  left_put_pub.publish(empty_msg);
483  break;
484  case RAISE_RIGHT_HAND:
485  right_get_pub.publish(empty_msg);
486  break;
487  case PUT_DOWN_RIGHT_HAND:
488  right_put_pub.publish(empty_msg);
489  break;
490  case LEFT_HAND_GRIP:
491  bool_msg.data = true;
492  left_grip_pub.publish(bool_msg);
493  break;
494  case LEFT_HAND_OPEN:
495  bool_msg.data = false;
496  left_grip_pub.publish(bool_msg);
497  break;
498  case RIGHT_HAND_GRIP:
499  bool_msg.data = true;
500  right_grip_pub.publish(bool_msg);
501  break;
502  case RIGHT_HAND_OPEN:
503  bool_msg.data = false;
504  right_grip_pub.publish(bool_msg);
505  break;
506  }
507 }
508 
509 void NLPModuleRos::pubWelcomeYes(bool enable_welcome)
510 {
511  std_msgs::Bool msg;
512  msg.data = enable_welcome;
513  welcome_yes_pub.publish(msg);
514 }
515 
516 void NLPModuleRos::pubWelcomeKp(const std::string kp_name)
517 {
518  std_msgs::String msg;
519  msg.data = kp_name;
520  welcome_kp_pub.publish(msg);
521 }
522 
523 // 控制机器人进行前进、后退、左转、右转等动作
524 void NLPModuleRos::pubMoveControl(const int robot_action)
525 {
526  geometry_msgs::Twist twist;
527  twist.linear.x = 0;
528  twist.linear.y = 0;
529  twist.linear.z = 0;
530  twist.angular.x = 0;
531  twist.angular.y = 0;
532  twist.angular.z = 0;
533  switch (robot_action)
534  {
535  case TAKE_A_STEP_FORWARD:
536  twist.linear.x = 0.15;
537  mov_control_pub.publish(twist);
538  break;
539 
541  twist.linear.x = -0.15;
542  mov_control_pub.publish(twist);
543 
544  break;
545  case TURN_LEFT:
546  twist.angular.z = 0.78;
547  mov_control_pub.publish(twist);
548  break;
549 
550  case TURN_RIGHT:
551  twist.angular.z = -0.78;
552  mov_control_pub.publish(twist);
553  break;
554  }
555 }
556 
557 void NLPModuleRos::subscribeOfflineRecogResult(const xbot_talker::recog_result msg)
558 {
559  ROS_INFO_STREAM("recog_result is :" << msg.recog_result << " |recog_accuracy is :" << msg.recog_accuracy
560  << std::endl);
561 
562  std::ofstream result_log(log_path + "/recog_result_log.txt", std::ios::app);
563  if (result_log.is_open())
564  {
565  result_log << log_count_ << ":" << msg.recog_result << std::endl;
566  log_count_++;
567  }
568  else
569  {
570  ROS_ERROR_STREAM("LOG ERROR");
571  }
572  result_log.close();
573  // 判断识别结果是否有效.
574  bool ret = result_handle.resultIsValid(msg.recog_result);
575  if (ret == false)
576  {
577  // 无效的识别结果意味着录音时间段内没有人说话,播放“没有人说话吗?那我先退下了”提示音并进入唤醒模式
578  std::string sorry_prompt_wav = "play " + base_path + "/defaultconfig/audio/none_speech.wav";
579  system(sorry_prompt_wav.c_str());
580  //enable_chat_ = false;
581  pubStartAwaken(true);
582  //pubStartRecog(true, true);
583  }
584  else if (msg.recog_accuracy < 15)
585  {
586  // 离线识别准确度小于15,可认定有人说话但说的与定义好的语法关键词没有任何关系
587  // 播放“不知道怎么回答了,请重新唤醒我吧”提示音,并进入唤醒模式
588  std::string sorry_prompt_wav = "play " + base_path + "/defaultconfig/audio/dontknow.wav";
589  system(sorry_prompt_wav.c_str());
590  //enable_chat_ = false;
591  pubStartAwaken(true);
592  pubStartRecog(true, true);
593  }
594  else if (msg.recog_accuracy < 35)
595  {
596  // 离线识别准确度在20-35之间,可认为用户说了语法关键词,但因为噪声等原因导致准确度很低,为避免出现误操作,需要提示用户确认一遍
597  // 播放“识别不够准确,请再说一遍命令词吧”提示音,并进入语音识别模式
598  std::string sorry_prompt_wav = "play " + base_path + "/defaultconfig/audio/low_SC.wav";
599  system(sorry_prompt_wav.c_str());
600  if (enable_chat_)
601  {
602  pubStartRecog(true, true);
603  }
604  else
605  {
606  pubStartRecog(true, false);
607  }
608  }
609  else
610  {
611  // 根据定义的应答策略检测识别到的关键词的识别策略.
612  result_handle.keywordDetection();
613  // 根据应答策略进行响应.
614  result_handle.keywordResponse(base_path + "/cache/wav");
615 
616  // 监测是否需要机器人控制以及控制类型
617  int robot_action = result_handle.actionDetect();
618  if (robot_action == START_CHAT)
619  {
620  enable_chat_ = true;
621  pubStartRecog(true, true);
622  }
623  else if ((robot_action >= 3) && (robot_action <= 14))
624  {
625  if (robot_action < 7)
626  {
627  pubMoveControl(robot_action);
628  sleep(1);
629  }
630  else if (robot_action >= 7)
631  {
632  pubArmControl(robot_action);
633  sleep(1);
634  }
635  if (enable_chat_)
636  {
637  pubStartRecog(true, true);
638  }
639  else
640  {
641  //pubStartAwaken(true);
642  pubStartRecog(true, true);
643 
644  }
645  }
646  else if (robot_action == CLOSE_CHAT)
647  {
648  pubStartRecog(false, false);
649  ROS_INFO_STREAM("-------- The conversation is closed! --------");
650  ROS_INFO_STREAM("--If you want to start asr module, say the awaken_word again! --");
651  //pubStartAwaken(true);
652  enable_chat_ = true;
653  }
654  else if (robot_action == BACK_TO_ORIGINAL_LOCATION)
655  {
656  pubWelcomeYes(true);
657  pubWelcomeKp("kp_origin");
658  pubStartRecog(false, false);
659  pubStartAwaken(true);
660  enable_chat_ = true;
661  }
662  else if (robot_action == NAVI_TO_FANGZONG)
663  {
664  pubWelcomeYes(true);
665  pubWelcomeKp("kp_fangyang");
666  pubStartRecog(true, false);
667  //pubStartAwaken(true);
668  enable_chat_ = true;
669  }
670  else if (robot_action == NAVI_TO_CHANGZONG)
671  {
672  pubWelcomeYes(true);
673  pubWelcomeKp("kp_cxm");
674  pubStartRecog(true, false);
675  //pubStartAwaken(true);
676  enable_chat_ = true;
677  }
678  else
679  {
680  // 控制asr开启新一轮语音识别
681  if (enable_chat_)
682  {
683  pubStartRecog(true, true);
684  }
685  else
686  {
687  pubStartAwaken(true);
688  }
689  }
690  }
691  result_handle.uninitNLP();
692 }
693 
694 void NLPModuleRos::subscribeOnlineRecogResult(const xbot_talker::online_asr_result msg)
695 {
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())
700  {
701  result_log << log_count_ << ":" << msg.online_asr_result << std::endl;
702  log_count_++;
703  }
704  else
705  {
706  ROS_ERROR_STREAM("LOG ERROR");
707  }
708  result_log.close();
709 
710  // 判断识别结果是否有效.
711  bool ret = result_handle.resultIsValid(msg.online_asr_result);
712  if (ret == false)
713  {
714  // 无效的识别结果意味着录音时间段内没有人说话,播放“没有人说话吗?那我先退下了”提示音并进入唤醒模式
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);
719  enable_chat_ = true;
720  }
721  else
722  {
723  // 设置图灵机器人对话请求参数
724  tuling_robot.setAskJson(msg.online_asr_result);
725  // 请求图灵机器人接口,获取回答
726  tuling_robot.callTulingApi();
727  // 从图灵机器人的完整json回答中解析出最终需要的text回答
728  tuling_answer_text_ = tuling_robot.textFromJson();
729  ROS_INFO_STREAM("TuLing robot answer is:" << tuling_answer_text_ << std::endl);
730  // 一次回答后释放资源
731  tuling_robot.uninitTuling();
732  result_handle.resultIsValid(tuling_answer_text_);
733  bool has_answer = result_handle.keywordDetection();
734 
735  if (has_answer == true)
736  {
737  // 根据应答策略进行响应.
738  result_handle.keywordResponse(base_path + "/cache/wav");
739 
740  // 监测是否需要机器人控制以及控制类型
741  int robot_action = result_handle.actionDetect();
742  if (robot_action == START_CHAT)
743  {
744  enable_chat_ = true;
745  pubStartRecog(true, true);
746  }
747  else if ((robot_action >= 3) && (robot_action <= 14))
748  {
749  if (robot_action < 7)
750  {
751  pubMoveControl(robot_action);
752  sleep(1);
753  }
754  else if (robot_action >= 7)
755  {
756  pubArmControl(robot_action);
757  sleep(1);
758  }
759  if (enable_chat_)
760  {
761  pubStartRecog(true, true);
762  }
763  else
764  {
765  pubStartAwaken(true);
766  }
767  }
768  else if (robot_action == CLOSE_CHAT)
769  {
770  pubStartRecog(false, false);
771  ROS_INFO_STREAM("-------- The conversation is closed! --------");
772  ROS_INFO_STREAM("--If you want to start asr module, say the awaken_word again! --");
773  pubStartAwaken(true);
774  //enable_chat_ = false;
775  }
776  else if (robot_action == BACK_TO_ORIGINAL_LOCATION)
777  {
778  pubWelcomeYes(true);
779  pubWelcomeKp("kp_origin");
780  pubStartRecog(false, false);
781  pubStartAwaken(true);
782  //enable_chat_ = false;
783  }
784  else if (robot_action == NAVI_TO_FANGZONG)
785  {
786  pubWelcomeYes(true);
787  pubWelcomeKp("kp_fangyang");
788  pubStartRecog(false, false);
789  pubStartAwaken(true);
790  //enable_chat_ = false;
791  }
792  else if (robot_action == NAVI_TO_CHANGZONG)
793  {
794  pubWelcomeYes(true);
795  pubWelcomeKp("kp_cxm");
796  pubStartRecog(true, false);
797  pubStartAwaken(true);
798  //enable_chat_ = false;
799  }
800  else
801  {
802  // 控制asr开启新一轮语音识别
803  if (enable_chat_)
804  {
805  pubStartRecog(true, true);
806  }
807  else
808  {
809  pubStartAwaken(true);
810  pubStartRecog(true, true);
811  }
812  }
813  }
814  else
815  {
816  TextToSpeech text_to_speech;
817  bool ret;
818  ret = text_to_speech.audioConverter(base_path + "/cache/wav", tuling_answer_text_.c_str());
819  if (enable_chat_)
820  {
821  pubStartRecog(true, true);
822  }
823  else
824  {
825  pubStartAwaken(true);
826  }
827  }
828  }
829  result_handle.uninitNLP();
830 }
831 
832 /**************************************************
833 ************* Ros Awaken Module *******************
834 ***************************************************/
836 {
837 }
839 {
840 }
841 
843 {
844  advertiseTopics();
845  subscribeTopics();
846  // 获取参数
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));
852 
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/"));
856 
857  awaken_nodehandle.param("/awaken_sample/audio_channel", audio_channel, int(1));
858  awaken_nodehandle.param("/awaken_sample/record_time", record_time, int(60));
859 
860  awaken_module.loginAndSetParams(base_path, pcm_file, audio_channel);
861 
862  ROS_INFO_STREAM("--------Voice wake up module is ready to be waken up!--------");
863 }
864 
866 {
867  is_awaken_pub = awaken_nodehandle.advertise<xbot_talker::awaken_status>("xbot_talker/awaken_status", 100);
868 }
869 
871 {
872  start_awaken_sub = awaken_nodehandle.subscribe(std::string("xbot_talker/enable_awake"), 10,
874 }
875 
876 void AwakenModuleRos::pubStartRecog(bool is_awaken)
877 {
878  xbot_talker::awaken_status awaken_status;
879  awaken_status.is_awaken = is_awaken;
880  is_awaken_pub.publish(awaken_status);
881 }
882 
884 {
885  while (true)
886  {
887  if (awaken_module.is_awaken)
888  {
889  if (awaken_mode == "mic")
890  {
891  awaken_module.stopRecordThroughMIC();
892  }
893  if (enable_record_save == true)
894  {
895  awaken_module.saveRecordDataToFile();
896  }
897  // 播放提示音提醒唤醒成功
898  std::string dialogue_prompt_wav = "play " + base_path + "/defaultconfig/audio/wozai.wav";
899  system(dialogue_prompt_wav.c_str());
900  // 开启离线命令词识别
901  pubStartRecog(true);
902  awaken_module.is_awaken = false;
903  break;
904  }
905  else
906  {
907  continue;
908  }
909  }
910 }
911 
912 void AwakenModuleRos::subscribeStartAwaken(const std_msgs::BoolConstPtr msg)
913 {
914  if (msg->data == true)
915  {
916  std::thread check(&AwakenModuleRos::isWaken, this);
917  awaken_module.awakenInit();
918  if (awaken_mode == "file")
919  {
920  awaken_module.getPcmFileData();
921  awaken_module.dataLoopAwaken();
922  }
923  else
924  {
925  awaken_module.recordThroughMIC(record_time, enable_record_save);
926  // TODO:可打断模式下,需要改为在此处关闭录音,取消下行注释即可
927  // awaken_module.stopRecordThroughMIC();
928  }
929  check.join();
930  awaken_module.uninitAsr();
931  }
932 }
933 
934 /**************************************************
935 ************* Ros TTS Module *******************
936 ***************************************************/
937 
939 {
940 }
942 {
943 }
945 {
946  requestServices();
947  responseServices();
948  // 获取参数
949  tts_nodehandle.param("/tts_sample/base_path", base_path, std::string("~/catkin_ws/src/xbot_talker"));
950  tts_nodehandle.param("/tts_sample/audio_save_path", audio_save_path,
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"));
953 
954  tts_nodehandle.param("/tts_sample/audio_channel", audio_channel, int(1));
955 
956  // 科大讯飞asr登录以及语法参数配置
957  CommonConfig& xunfei_config = CommonConfig::get_instance();
958  xunfei_config.loginToXunfei(base_path);
959 
960  ROS_INFO_STREAM("--------TextToSpeech module is ready to start.--------");
961 }
962 
964 {
965  tts_server = tts_nodehandle.advertiseService(std::string("/xbot/xbot_tts"), &TTSModuleRos::ttsCallback, this);
966  play_server = tts_nodehandle.advertiseService(std::string("/xbot/play"), &TTSModuleRos::playCallback, this);
967 
968 }
969 
970 bool TTSModuleRos::playCallback(xbot_talker::play::Request &req, xbot_talker::play::Response &res){
971  if (req.mode == 1){
972  std::string audiofile = req.audio_path;
973  std::string dialogue_prompt_wav = "play " + audiofile;
974  system(dialogue_prompt_wav.c_str());
975  }
976  if (req.mode == 2){
977  ROS_INFO("----------start to request the tts service-----------");
978 
979  TextToSpeech tts_test;
980  string text = req.tts_text;
981  tts_test.audioConverter(log_path, text.c_str());
982  ROS_INFO("tts done.");
983  }
984  res.success = true;
985  return true;
986 }
987 
988 
990 {
991  tts_client = tts_nodehandle.serviceClient<xbot_talker::xbot_tts>(std::string("xbot/xbot_tts"));
992 }
993 
994 // xbot_tts 服务的回调函数
995 bool TTSModuleRos::ttsCallback(xbot_talker::xbot_tts::Request& req, xbot_talker::xbot_tts::Response& res)
996 {
997  if (req.start_tts)
998  {
999  ROS_INFO("----------start to request the tts service-----------");
1000 
1001  TextToSpeech tts_test;
1002  string text = req.tts_text;
1003  tts_test.audioConverter(log_path, text.c_str());
1004  ROS_INFO("tts done.");
1005  res.success = true;
1006 
1007  return true;
1008  }
1009 }
void pubOfflineRecogResult(const std::string result, const int accuracy)
void pubStartRecog(bool is_awaken, bool enable_chat)
void pubMoveControl(const int robot_action)
void subscribeTopics()
void advertiseService()
ROSCPP_DECL bool check()
void pubWelcomeYes(bool enable_welcome)
std::string grammar_path
ros::Publisher recog_result_pub
bool enable_record_save
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相关参数.
Definition: asr_online.cpp:34
void pubStartAwaken(bool enable_awake)
void uninitAsr()
一次识别结束后释放资源.
CSVOperation csv_file
ros::Subscriber is_awaken_sub
struct DataBuff pcm_buff
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 pcm_file
std::string readFileAsString(const std::string file_path)
void setAsrParams(const std::string base_path, const std::string pcm_file, const int channel)
设置语音模块需外部传入的路径等参数.
Definition: asr_online.cpp:28
std::string log_path
std::vector< std::string > offline_result_vector
std::string offline_recog_result
void uninitAsr()
一次识别结束后释放资源.
Definition: asr_online.cpp:268
bool enable_xfei_online
bool enable_baidu_online
char * dataLoopRecog()
将全部音频数据循环写入科大讯飞接口进行识别并获取完整的json识别结果.
std::string base_path
void pubStartRecog(bool is_awaken)
std::string resultFromJson()
从完整的json语音识别结果中解析出需要的字符串结果.
Definition: asr_online.cpp:241
struct DataBuff recordThroughMIC(const float record_time, bool enable_audio_save)
录音接口.
#define ROS_INFO(...)
char * data
Definition: file_operation.h:8
bool param(const std::string &param_name, T &param_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_结构体里存储的音频用于百度在线语音识别并获取识别结果.
Definition: asr_online.cpp:88
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.
Definition: asr_online.cpp:55
std::string xfei_online_result
void pubWelcomeKp(const std::string kp_name)
struct DataBuff recordThroughMIC(const float record_time, bool enable_audio_save)
录音接口.
Definition: asr_online.cpp:187
void subscribeStartAwaken(const std_msgs::BoolConstPtr)
char * recog_result_json
#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 advertiseTopics()
void writeRowData(std::string csv_file, std::vector< std::string > row_vector)
#define ROS_ERROR_STREAM(args)
BaiduAsrOnline baidu_sr_online
std::string asr_params_
void getPcmFileData()
读取pcm文件里的音频数据,并将数据的内容和数据大小存入pcm_data_结构体.
Definition: asr_online.cpp:83
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数据接口.
Definition: asr_online.cpp:158


xbot_talker
Author(s): wangxiaoyun
autogenerated on Sat Oct 10 2020 03:27:54