1 #ifndef XBOT_TALKER_ROS_H_ 2 #define XBOT_TALKER_ROS_H_ 3 #include <std_msgs/Bool.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" 18 #include "xbot_talker/play.h" 19 #include "xbot_talker/chat.h" 45 bool requestChat(xbot_talker::chat::Request &req, xbot_talker::chat::Response &res);
49 bool requestKeywordConfig(xbot_talker::keyword_config::Request& req, xbot_talker::keyword_config::Response& res);
111 void pubStartRecog(
bool is_awaken,
bool enable_chat);
139 bool requestDialogConfig(xbot_talker::nlpdialog_config::Request& req, xbot_talker::nlpdialog_config::Response& res);
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);
148 void pubStartAwaken(
bool enable_awake);
159 void subscribeOfflineRecogResult(
const xbot_talker::recog_result);
160 void subscribeOnlineRecogResult(
const xbot_talker::online_asr_result);
170 bool enable_chat_ =
true;
193 void subscribeStartAwaken(
const std_msgs::BoolConstPtr);
194 void pubStartRecog(
bool is_awaken);
221 void responseServices();
222 void requestServices();
235 bool playCallback(xbot_talker::play::Request &req, xbot_talker::play::Response &res);
241 bool ttsCallback(xbot_talker::xbot_tts::Request& req, xbot_talker::xbot_tts::Response& res);
ros::NodeHandle tts_nodehandle
void pubOfflineRecogResult(const std::string result, const int accuracy)
ros::ServiceServer play_server
ros::Publisher recog_result_pub
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
ros::Publisher right_get_pub
XfeiSpeechRecog xfei_sr_offline
ros::Publisher right_grip_pub
ros::ServiceClient tts_client
ros::Subscriber is_awaken_sub
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 awaken_params_
std::vector< std::string > offline_result_vector
std::string offline_recog_result
std::string tuling_answer_text_
百度语音识别模块接口头文件. TODO: 还需要添加版权、版本等信息
std::string audio_save_path
ros::Publisher left_grip_pub
ros::Publisher start_awaken_pub
ros::Publisher left_put_pub
ros::ServiceServer tts_server
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
ros::ServiceServer keyword_config_service
ros::ServiceServer chat_server_
std::string xfei_online_result
ros::Publisher welcome_kp_pub
ros::Publisher right_put_pub
AwakenOffline awaken_module
ros::Publisher sound_mute
std::string xunfei_online_asr_params_
ros::Publisher is_awaken_pub
语音识别结果处理与机器人交互模块. TODO: 还需要添加版权、版本等信息
ros::Subscriber awaken_result_sub
ResultFeedback result_handle
ros::Publisher left_get_pub
BaiduAsrOnline baidu_sr_online
ros::Subscriber online_result_sub
void pubOnlineRecogResult(const std::string result)
ros::Subscriber recog_result_sub