9 from std_msgs.msg
import Bool, UInt8, String
10 from xbot_talker.msg
import actionmode, actionmode_ros, action, action_ros, dialogue_ros, dialogue
18 sys.setdefaultencoding(
'utf-8')
23 rospy.init_node(
'dialogue_config',anonymous=
False)
34 def nlp_config(self, keyword, answer,action,action_mode):
35 rospy.wait_for_service(
'/xbot_talker/nlp_dialog_config')
36 nlp_dialog_config = rospy.ServiceProxy(
'/xbot_talker/nlp_dialog_config', nlpdialog_config)
37 res=nlp_dialog_config(keyword,answer,action,action_mode)
43 rospy.wait_for_service(
'/xbot_talker/asr_keyword_config')
44 asr_keyword_config = rospy.ServiceProxy(
'/xbot_talker/asr_keyword_config', keyword_config)
45 res=asr_keyword_config(keyword)
51 filename = os.popen(
'rospack find xbot_talker').read().strip() +
'/userconfig/json/action_mode.json' 52 if req.get_actionmode_req:
53 with open(filename,
'r') as f: 55 actionmodes = data['ActionMode']
56 actionmode_list = actionmode_ros()
57 for i
in range(len(actionmodes)):
59 tem.actionmode_desc = actionmodes[i][
'description']
60 tem.actionmode_name = actionmodes[i][
'name']
61 tem.actionmode_flag = actionmodes[i][
'flag']
62 actionmode_list.actionmode_ros.append(tem)
63 print(actionmode_list)
64 return call_actionmodeResponse(actionmode_list)
66 rospy.logwarn(
"error: If you want to get the actionmodes, please set the get_actionmode_req True.")
70 filename = os.popen(
'rospack find xbot_talker').read().strip() +
'/userconfig/json/action.json' 71 if req.get_action_req:
72 with open(filename,
'r') as f: 74 actions = data['Action']
75 action_list = action_ros()
76 for i
in range(len(actions)):
78 tem.action_desc = actions[i][
'description']
79 tem.action_name = actions[i][
'name']
80 tem.action_flag = actions[i][
'flag']
81 action_list.action_ros.append(tem)
82 rospy.loginfo(action_list)
83 return call_actionResponse(action_list)
85 rospy.logwarn(
"error: If you want to get the actions, please set the get_action_req True.")
89 filename = os.popen(
'rospack find xbot_talker').read().strip() +
'/userconfig/json/dialogue.json' 90 with open(filename,
'r') as f: 92 dialogues = data['Dialogue']
95 for i
in range(len(dialogues)):
96 if req.keyword == dialogues[i][
'keyword']:
97 rospy.logwarn(
"False: This keyword already exist!")
98 return add_dialogueResponse(1)
100 now_time = datetime.datetime.now().strftime(
'%Y-%m-%d %H:%M:%S')
102 new_dialogue = {
'keyword':req.keyword,
'answer':req.answer,
'action':req.action,
'action_mode':req.action_mode,
'update_time':now_time}
103 dialogues.append(new_dialogue)
104 data[
'Dialogue'] = dialogues
105 with codecs.open(filename,
'w',
'utf-8')
as file:
106 json.dump(data, file, indent=4, ensure_ascii=
False)
108 print(chardet.detect(req.keyword))
109 filename_bnf = os.popen(
'rospack find xbot_talker').read().strip() +
'/userconfig/grammar.bnf' 110 with open(filename_bnf,
'r') as f: 112 print(chardet.detect(data_bnf)) 113 content = data_bnf.rfind(';')
115 data_bnf = data_bnf[:content]+
'|'+req.keyword+data_bnf[content:]
116 with open(filename_bnf,
'w')
as f:
118 add_dialogue_enable =
True 119 rospy.loginfo(
"Dialogue config【" + req.keyword +
"】successful!")
122 build_grammar_command =
'roslaunch xbot_talker build_grammar.launch' 123 build_grammar = subprocess.Popen(build_grammar_command, shell=
True,
124 stdout=subprocess.PIPE,
125 stderr=subprocess.STDOUT,
129 errcorde = self.
nlp_config(req.keyword,req.answer,req.action,req.action_mode)
131 rospy.logwarn(
"False: This keyword already exist in answer_dic!")
132 return add_dialogueResponse(1)
136 rospy.logwarn(
"False: reset keyword failed!")
137 return add_dialogueResponse(2)
139 return add_dialogueResponse(0)
144 if req.get_history_record:
145 filename = os.popen(
'rospack find xbot_talker').read().strip() +
'/userconfig/json/dialogue.json' 146 with open(filename,
'r') as f: 148 dialogues = data['Dialogue']
149 dialogue_list = dialogue_ros()
152 tem.keyword = dialogues[-10+i][
'keyword']
153 tem.answer = dialogues[-10+i][
'answer']
154 tem.update_time = dialogues[-10+i][
'update_time']
155 tem.action = dialogues[-10+i][
'action']
156 tem.action_mode = dialogues[-10+i][
'action_mode']
157 dialogue_list.dialogue_ros.append(tem)
158 rospy.loginfo(dialogue_list)
159 return history_recordResponse(dialogue_list)
161 rospy.logwarn(
"error: If you want to get the dialogue history record, please set the get_history_record True.")
167 filename = os.popen(
'rospack find xbot_talker').read().strip() +
'/userconfig/json/dialogue.json' 168 with open(filename,
'r') as f: 170 dialogues = data['Dialogue']
172 for i
in range(len(dialogues)):
173 if req.version_info == dialogues[i][
'update_time']:
176 if config_status == 1:
177 rospy.logwarn(
"False: roolback_dialogue failed!")
178 return roolback_dialogueResponse(config_status)
181 data[
'Dialogue'] = dialogues
182 with codecs.open(filename,
'w',
'utf-8')
as file:
183 json.dump(data, file, indent=4, ensure_ascii=
False)
185 filename_bnf = os.popen(
'rospack find xbot_talker').read().strip() +
'/userconfig/grammar.bnf' 186 with open(filename_bnf,
'r') as f: 188 roolback_keyword = dialogues[i]['keyword'].encode(
'utf-8')
189 content_bnf = data_bnf.rfind(roolback_keyword)
190 if content_bnf != -1:
191 data_bnf = data_bnf[:content_bnf+len(roolback_keyword)]+
';' 193 with open(filename_bnf,
'w')
as f:
198 build_grammar_command =
'roslaunch xbot_talker build_grammar.launch' 199 build_grammar = subprocess.Popen(build_grammar_command, shell=
True,
200 stdout=subprocess.PIPE,
201 stderr=subprocess.STDOUT,
206 filename_csv = os.popen(
'rospack find xbot_talker').read().strip() +
'/defaultconfig/answer_dic.csv' 207 with open(filename_csv,
'r') as f: 208 data_csv = csv.reader(f) 210 for item
in data_csv:
211 new_data_csv.append(item)
212 if item[0]==roolback_keyword:
215 with open(filename_csv,
'w')
as f:
216 writer = csv.writer(f)
217 writer.writerows(new_data_csv)
220 self.
nlp_config(
"back_config",
"back_config",0,0)
221 rospy.loginfo(
"Successful: roolback_dialogue succeed!")
222 return roolback_dialogueResponse(config_status)
226 while rospy.is_shutdown:
227 rospy.loginfo(
"Stopping ...")
232 if __name__ ==
'__main__':
def call_actionmodes(self, req)
def asr_config(self, keyword)
def call_actions(self, req)
def add_dialogues(self, req)
def roolback_dialogue(self, req)
def get_history(self, req)
def nlp_config(self, keyword, answer, action, action_mode)