read_all_files_and_recog.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <iostream>
3 #include <thread>
4 #include "asr/baidu/asr_online.h"
5 #include "common_config.h"
6 #include "file_operation.h"
8 
11 int count = 0;
12 std::string base_path;
13 std::string log_path;
14 
15 // 离线语音识别线程
17 {
18  char* recog_result;
19  asr_module.initAsr();
20  recog_result = asr_module.dataLoopRecog();
21  ROS_INFO_STREAM("Offline asr result is :" << recog_result << std::endl);
22  std::ofstream result_log(log_path + "/test_result_log.txt", std::ios::app);
23  if (result_log.is_open())
24  {
25  result_log << count << "\n" << recog_result << std::endl;
26  }
27  else
28  {
29  ROS_ERROR_STREAM("LOG ERROR");
30  }
31  result_log.close();
32 
33  asr_module.uninitAsr();
34 }
35 
36 // 在线语音识别线程
38 {
39  char* recog_result_online;
40  recog_result_online = asr_online_module.runAsrAndRecog();
41  ROS_INFO_STREAM("Online asr result is :" << recog_result_online << std::endl);
42  std::ofstream result_log(log_path + "/test_online_result_log.txt", std::ios::app);
43  if (result_log.is_open())
44  {
45  result_log << count << "\n" << recog_result_online << std::endl;
46  }
47  else
48  {
49  ROS_ERROR_STREAM("LOG ERROR");
50  }
51  result_log.close();
52  asr_online_module.uninitAsr();
53 }
54 int main(int argc, char** argv)
55 {
56  setlocale(LC_ALL, "");
57 
58  bool enable_online;
59  bool enable_offline;
60  std::string asr_params_;
61  std::string grammar_path;
62  std::string pcm_file;
63  int audio_channel;
64  std::string test_dir_path;
65  ros::init(argc, argv, "asr_sample");
66 
67  ros::NodeHandle asr_nodehandle;
68  // 获取参数
69  asr_nodehandle.param("/asr_sample/enable_online", enable_online, bool(false));
70  asr_nodehandle.param("/asr_sample/enable_offline", enable_offline, bool(true));
71 
72  asr_nodehandle.param("/asr_sample/base_path", base_path, std::string("~/catkin_ws/src/xbot_talker"));
73  asr_nodehandle.param("/asr_sample/test_dir_path", test_dir_path, std::string("~/catkin_ws/src/xbot_talker"));
74  asr_nodehandle.param("/asr_sample/grammar_path", grammar_path,
75  std::string("~/catkin_ws/src/xbot_talker/cache/grammar_config"));
76  asr_nodehandle.param("/asr_sample/pcm_file", pcm_file,
77  std::string("~/catkin_ws/src/xbot_talker/defaultconfig/audio/nihao_test.pcm"));
78 
79  asr_nodehandle.param("/asr_sample/log_path", log_path, std::string("~/catkin_ws/src/xbot_talker/cache/log"));
80 
81  asr_nodehandle.param("/asr_sample/audio_channel", audio_channel, int(1));
82 
83  if (enable_offline == true)
84  {
85  // 科大讯飞asr登录以及语法参数配置
86  CommonConfig& xunfei_config = CommonConfig::get_instance();
87  xunfei_config.loginToXunfei(base_path);
88  asr_params_ = xunfei_config.configGramParas(base_path, grammar_path);
89  }
90  // 设置百度在线语音识别相关参数
91  if (enable_online == true)
92  {
93  asr_online_module.initAndConfigAsr();
94  asr_online_module.speechGetToken();
95  }
96  std::cout << "Test dir is :" << test_dir_path << std::endl;
97  FileOperation test_file;
98  std::vector<std::string> files;
99  test_file.getAllFilesName(test_dir_path, files);
100 
101  for (int i = 0; i < files.size(); i++)
102  {
103  asr_module.setAsrParams(base_path, test_dir_path + "/" + files[i], asr_params_, audio_channel);
104  asr_online_module.setAsrParams(base_path, test_dir_path + "/" + files[i], audio_channel);
105 
106  if (enable_offline && enable_online)
107  {
108  asr_module.getPcmFileData();
109  asr_online_module.getPcmFileData();
110 
111  std::thread offlineThread(offlineRecog);
112  std::thread onlineThread(onlineRecog);
113  onlineThread.join();
114  offlineThread.join();
115  }
116  else if (enable_offline == true)
117  {
118  asr_module.getPcmFileData();
119 
120  std::thread offlineThread(offlineRecog);
121  offlineThread.join();
122  }
123  else if (enable_online == true)
124  {
125  asr_online_module.getPcmFileData();
126 
127  std::thread onlineThread(onlineRecog);
128  onlineThread.join();
129  }
130  count++;
131  std::cout << files[i] << std::endl;
132  }
133  return 0;
134 }
void initAsr()
科大讯飞识别模块的初始化.
static CommonConfig & get_instance()
void initAndConfigAsr()
百度语音识别模块的初始化,设置asr相关参数.
Definition: asr_online.cpp:34
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void uninitAsr()
一次识别结束后释放资源.
std::string log_path
void loginToXunfei(const std::string base_path)
科大讯飞语音识别模块接口头文件. TODO: 还需要添加版权、版本等信息
void onlineRecog()
std::string base_path
void offlineRecog()
void setAsrParams(const std::string base_path, const std::string pcm_file, const int channel)
设置语音模块需外部传入的路径等参数.
Definition: asr_online.cpp:28
void uninitAsr()
一次识别结束后释放资源.
Definition: asr_online.cpp:268
百度语音识别模块接口头文件. TODO: 还需要添加版权、版本等信息
char * dataLoopRecog()
将全部音频数据循环写入科大讯飞接口进行识别并获取完整的json识别结果.
XfeiSpeechRecog asr_module
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void setAsrParams(const std::string base_path, const std::string pcm_file, const std::string params, const int channel)
设置语音模块需外部传入的路径等参数.
char * runAsrAndRecog()
将pcm_data_结构体里存储的音频用于百度在线语音识别并获取识别结果.
Definition: asr_online.cpp:88
BaiduAsrOnline asr_online_module
void speechGetToken()
获取百度在线语音识别的Token.
Definition: asr_online.cpp:55
int main(int argc, char **argv)
#define ROS_INFO_STREAM(args)
std::string configGramParas(const std::string base_path, const std::string grammar_file)
#define ROS_ERROR_STREAM(args)
void getPcmFileData()
读取pcm文件里的音频数据,并将数据的内容和数据大小存入pcm_data_结构体.
Definition: asr_online.cpp:83
void getPcmFileData()
读取pcm文件里的音频数据,并将数据的内容和数据大小存入pcm_data_.
void getAllFilesName(std::string dir_path, std::vector< std::string > &files_name)


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