xbot_talker_ros.h
Go to the documentation of this file.
1 #ifndef XBOT_TALKER_ROS_H_
2 #define XBOT_TALKER_ROS_H_
3 #include <std_msgs/Bool.h>
4 #include <iostream>
6 #include "asr/baidu/asr_online.h"
7 #include "file_operation.h"
8 #include "nlp/nlp_feedback.h"
9 #include "tts/text_to_speech.h"
10 #include "xbot_talker/awaken_status.h"
11 #include "xbot_talker/keyword_config.h"
12 #include "xbot_talker/nlpdialog_config.h"
13 #include "xbot_talker/online_asr_result.h"
14 #include "xbot_talker/recog_result.h"
15 #include "xbot_talker/xbot_tts.h"
17 #include "ros/ros.h"
18 #include "xbot_talker/play.h"
19 #include "xbot_talker/chat.h"
20 // 与asr模块相关的ROS操作的封装类
22 {
23 public:
25  {
26  }
28  std::string offline_recog_result;
29  std::string baidu_online_result;
30  std::string xfei_online_result;
31 
32  bool init();
33  void offlineRecog();
34  void onlineRecogXfei();
35  void onlineRecogBaidu();
36 
37 private:
39 
40  void advertiseTopics();
41  void subscribeTopics();
42  void advertiseService();
43 
45  bool requestChat(xbot_talker::chat::Request &req, xbot_talker::chat::Response &res);
46 
47 
49  bool requestKeywordConfig(xbot_talker::keyword_config::Request& req, xbot_talker::keyword_config::Response& res);
50 
51  /*********************
52  ** Ros Publishers
53  **********************/
57  /*********************
58  ** Ros Publisher Function
59  **********************/
60  void pubOfflineRecogResult(const std::string result, const int accuracy);
61  void pubOnlineRecogResult(const std::string result);
62  /*********************
63  ** Ros Subscribers
64  **********************/
66 
67  /*********************
68  ** Ros Subscribers Callbacks
69  **********************/
70  void subscribeAwakenStatus(const xbot_talker::awaken_status);
71 
72  /*********************
73  ** ASR variable
74  **********************/
79  bool use_mic;
81  std::string asr_params_;
83  std::string base_path;
84  std::string grammar_path;
85  std::string config_path;
86  std::string pcm_file;
87  std::string audio_save_path;
88  std::string log_path;
90  int log_count_ = 0;
92  float record_time;
94  std::vector<std::string> offline_result_vector;
95  struct DataBuff pcm_buff = { NULL, 0 };
101 
102 };
103 
104 // 与nlp模块相关的ROS操作的封装类
106 {
107 public:
108  NLPModuleRos();
109  ~NLPModuleRos();
110  bool init();
111  void pubStartRecog(bool is_awaken, bool enable_chat);
112 
113 private:
115 
116  void advertiseTopics();
117  void subscribeTopics();
118  void advertiseService();
119 
120  /*********************
121  ** Ros Publishers
122  **********************/
123  ros::Publisher start_awaken_pub; // 开始语音唤醒
124  ros::Publisher start_recog_pub; // 开始离线命令词识别
125  ros::Publisher mov_control_pub; // 机器人移动控制
128 
131 
134 
137 
139  bool requestDialogConfig(xbot_talker::nlpdialog_config::Request& req, xbot_talker::nlpdialog_config::Response& res);
140  /*********************
141  ** Ros Publisher Function
142  **********************/
143  void pubMoveControl(const int robot_action);
144  void pubArmControl(const int robot_action);
145  void pubWelcomeYes(bool enable_welcome);
146  void pubWelcomeKp(const std::string kp_name);
147 
148  void pubStartAwaken(bool enable_awake);
149  /*********************
150  ** Ros Subscribers
151  **********************/
155 
156  /*********************
157  ** Ros Subscribers Callbacks
158  **********************/
159  void subscribeOfflineRecogResult(const xbot_talker::recog_result);
160  void subscribeOnlineRecogResult(const xbot_talker::online_asr_result);
161 
162  /*********************
163  ** NLP variable
164  **********************/
165  std::string base_path;
166  std::string nlp_config_path;
167  std::string config_path;
168  std::string log_path;
170  bool enable_chat_ = true;
171  int fail_count_ = 0;
172  int log_count_ = 0;
173  std::string tuling_answer_text_;
176 };
177 
178 // 与awaken模块相关的ROS操作的封装类
180 {
181 public:
182  AwakenModuleRos();
183  ~AwakenModuleRos();
184  bool init();
185  void isWaken();
186 
187 private:
190 
191  void advertiseTopics();
192  void subscribeTopics();
193  void subscribeStartAwaken(const std_msgs::BoolConstPtr);
194  void pubStartRecog(bool is_awaken);
196  std::string awaken_params_;
197  std::string base_path;
198  std::string config_path;
199  std::string pcm_file;
200  std::string awaken_mode;
201  std::string audio_save_path;
202  std::string log_path;
205 
208 };
209 
210 // 与tts模块相关的ROS操作的封装类
212 {
213 public:
214  TTSModuleRos();
215  ~TTSModuleRos();
216  bool init();
217 
218 private:
220 
221  void responseServices();
222  void requestServices();
223 
224  /*********************
225  ** Ros TTS RequestServiceClient
226  **********************/
228 
229  /*********************
230  ** Ros TTS ResponseServiceServer
231  **********************/
234 
235  bool playCallback(xbot_talker::play::Request &req, xbot_talker::play::Response &res);
236 
237 
238  /*********************
239  ** Ros TTS ServiceServer Callbacks
240  **********************/
241  bool ttsCallback(xbot_talker::xbot_tts::Request& req, xbot_talker::xbot_tts::Response& res);
242 
243  /*********************
244  ** TTS variable
245  **********************/
246  std::string base_path;
247  std::string audio_save_path;
248  std::string log_path;
250 };
251 #endif
ros::NodeHandle tts_nodehandle
void pubOfflineRecogResult(const std::string result, const int accuracy)
ros::ServiceServer play_server
void subscribeTopics()
void advertiseService()
std::string grammar_path
ros::Publisher recog_result_pub
std::string awaken_mode
bool enable_record_save
ros::NodeHandle awaken_nodehandle
XfeiSpeechRecog xfei_sr_online
ros::Subscriber start_awaken_sub
bool requestKeywordConfig(xbot_talker::keyword_config::Request &req, xbot_talker::keyword_config::Response &res)
std::string nlp_config_path
std::string config_path
ros::Publisher right_get_pub
XfeiSpeechRecog xfei_sr_offline
std::string base_path
ros::Publisher right_grip_pub
ros::ServiceClient tts_client
CSVOperation csv_file
ros::Subscriber is_awaken_sub
struct DataBuff pcm_buff
std::string audio_save_path
std::string baidu_online_result
科大讯飞离线唤醒模块接口定义头文件. TODO: 还需要添加版权、版本等信息
ros::NodeHandle nlp_nodehandle
FileOperation config_file
科大讯飞语音识别模块接口头文件. TODO: 还需要添加版权、版本等信息
ros::NodeHandle asr_nodehandle
void subscribeAwakenStatus(const xbot_talker::awaken_status)
ros::Publisher mov_control_pub
std::string pcm_file
std::string log_path
std::string awaken_params_
std::vector< std::string > offline_result_vector
std::string offline_recog_result
std::string tuling_answer_text_
bool enable_xfei_online
TuLingRobot tuling_robot
百度语音识别模块接口头文件. TODO: 还需要添加版权、版本等信息
bool enable_baidu_online
std::string audio_save_path
ros::Publisher left_grip_pub
ros::Publisher start_awaken_pub
std::string base_path
ros::Publisher left_put_pub
ros::ServiceServer tts_server
std::string base_path
ros::Publisher start_recog_pub
ros::Publisher online_result_pub
std::string audio_save_path
bool requestChat(xbot_talker::chat::Request &req, xbot_talker::chat::Response &res)
ros::ServiceServer dialog_config_service
ros::Publisher welcome_yes_pub
std::string log_path
ros::ServiceServer keyword_config_service
std::string base_path
ros::ServiceServer chat_server_
std::string xfei_online_result
ros::Publisher welcome_kp_pub
ros::Publisher right_put_pub
char * recog_result_json
AwakenOffline awaken_module
std::string log_path
ros::Publisher sound_mute
std::string xunfei_online_asr_params_
void advertiseTopics()
ros::Publisher is_awaken_pub
语音识别结果处理与机器人交互模块. TODO: 还需要添加版权、版本等信息
ros::Subscriber awaken_result_sub
ResultFeedback result_handle
std::string config_path
ros::Publisher left_get_pub
std::string config_path
BaiduAsrOnline baidu_sr_online
std::string asr_params_
std::string pcm_file
ros::Subscriber online_result_sub
std::string log_path
void pubOnlineRecogResult(const std::string result)
ros::Subscriber recog_result_sub


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