dialogflow_client.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- encoding: utf-8 -*-
3 
4 import actionlib
5 import dialogflow as df
6 from google.protobuf.json_format import MessageToJson
7 import pprint
8 import Queue
9 import rospy
10 import threading
11 import uuid
12 
13 from audio_common_msgs.msg import AudioData
14 from sound_play.msg import SoundRequest
15 from sound_play.msg import SoundRequestAction
16 from sound_play.msg import SoundRequestGoal
17 from speech_recognition_msgs.msg import SpeechRecognitionCandidates
18 from std_msgs.msg import String
19 
20 from dialogflow_task_executive.msg import DialogResponse
21 
22 
23 class State(object):
24  IDLE = "IDLE"
25  SPEAKING = "SPEAKING"
26  LISTENING = "LISTENING"
27  THINKING = "THINKING"
28 
29  def __init__(self, init_state=None):
30  self._state = init_state or self.IDLE
31  self._last_state = None
32  self._last_changed = rospy.Time.now()
33 
34  def set(self, state):
35  if self._state != state:
36  self._last_state = self._state
37  self._state = state
38  rospy.loginfo(
39  "State: {} -> {}".format(self._last_state, self._state))
40  self._last_changed = rospy.Time.now()
41 
42  @property
43  def current(self):
44  return self._state
45 
46  @property
47  def last_state(self):
48  return self._last_state
49 
50  @property
51  def last_changed(self):
52  return self._last_changed
53 
54  def __eq__(self, state):
55  return self._state == state
56 
57  def __ne__(self, state):
58  return not self.__eq__(state)
59 
60 
61 class DialogflowClient(object):
62 
63  def __init__(self):
64  # project id for google cloud service
65  self.project_id = rospy.get_param("~project_id")
66  # language for dialogflow
67  self.language = rospy.get_param("~language", "ja-JP")
68 
69  # use raw audio data if enabled, otherwise use recognized STT data
70  self.use_audio = rospy.get_param("~use_audio", False)
71  # sample rate of audio data
72  self.audio_sample_rate = rospy.get_param("~audio_sample_rate", 16000)
73 
74  # use TTS feature
75  self.use_tts = rospy.get_param("~use_tts", True)
76 
77  # timeout for voice input activation by hotword
78  self.timeout = rospy.get_param("~timeout", 10.0)
79  # hotwords
80  self.enable_hotword = rospy.get_param("~enable_hotword", True)
81  self.hotword = rospy.get_param(
82  "~hotword", ["ねえねえ", "こんにちは", "やあ"])
83 
84  self.state = State()
85  self.session_id = None
86  self.session_client = df.SessionsClient()
87  self.queue = Queue.Queue()
88  self.last_spoken = rospy.Time(0)
89 
90  if self.use_tts:
91  self.sound_action = actionlib.SimpleActionClient(
92  "robotsound_jp", SoundRequestAction)
93  if not self.sound_action.wait_for_server(rospy.Duration(5.0)):
94  self.sound_action = None
95  else:
96  self.timer_speech = rospy.Timer(
97  rospy.Duration(0.1), self.speech_timer_cb)
98  else:
99  self.sound_action = None
100 
101  self.pub_res = rospy.Publisher(
102  "dialog_response", DialogResponse, queue_size=1)
103 
104  if self.use_audio:
105  self.audio_config = df.types.InputAudioConfig(
106  audio_encoding=df.enums.AudioEncoding.AUDIO_ENCODING_LINEAR_16,
107  language_code=self.language,
108  sample_rate_hertz=self.audio_sample_rate)
109  self.audio_data = None
110  self.sub_hotword = rospy.Subscriber(
111  "hotword", String, self.hotword_cb)
112  self.sub_audio = rospy.Subscriber(
113  "speech_audio", AudioData, self.input_cb)
114  else:
115  self.sub_speech = rospy.Subscriber(
116  "speech_to_text", SpeechRecognitionCandidates,
117  self.input_cb)
118 
119  self.df_thread = threading.Thread(target=self.df_run)
120  self.df_thread.daemon = True
121  self.df_thread.start()
122 
123  def speech_timer_cb(self, event=None):
124  if self.state != State.IDLE:
125  if (rospy.Time.now() - self.state.last_changed
126  > rospy.Duration(self.timeout)):
127  self.state.set(State.IDLE)
128  self.session_id = None
129 
130  def hotword_cb(self, msg):
131  if msg.data in self.hotword:
132  rospy.loginfo("Hotword received")
133  self.state.set(State.LISTENING)
134 
135  def input_cb(self, msg):
136  if not self.enable_hotword:
137  self.state.set(State.LISTENING)
138  elif not self.use_audio:
139  # catch hotword from string
140  self.hotword_cb(String(data=msg.transcript[0]))
141 
142  if self.state == State.LISTENING:
143  self.queue.put(msg)
144  rospy.loginfo("Received input")
145  else:
146  rospy.logdebug("Received input but ignored")
147 
148  def detect_intent_text(self, data, session):
149  query = df.types.QueryInput(
150  text=df.types.TextInput(
151  text=data, language_code=self.language))
152  return self.session_client.detect_intent(
153  session=session, query_input=query).query_result
154 
155  def detect_intent_audio(self, data, session):
156  query = df.types.QueryInput(audio_config=self.audio_config)
157  return self.session_client.detect_intent(
158  session=session, query_input=query,
159  input_audio=data).query_result
160 
161  def print_result(self, result):
162  rospy.loginfo(pprint.pformat(result))
163 
164  def publish_result(self, result):
165  msg = DialogResponse()
166  msg.header.stamp = rospy.Time.now()
167  if result.action is not 'input.unknown':
168  rospy.logwarn("Unknown action")
169  msg.query = result.query_text.encode("utf-8")
170  msg.action = result.action
171  msg.response = result.fulfillment_text.encode("utf-8")
172  msg.fulfilled = result.all_required_params_present
173  msg.parameters = MessageToJson(result.parameters)
174  msg.speech_score = result.speech_recognition_confidence
175  msg.intent_score = result.intent_detection_confidence
176  self.pub_res.publish(msg)
177 
178  def speak_result(self, result):
179  if self.sound_action is None:
180  return
181  msg = SoundRequest(
182  command=SoundRequest.PLAY_ONCE,
183  sound=SoundRequest.SAY,
184  volume=1.0,
185  arg=result.fulfillment_text.encode('utf-8'),
186  arg2=self.language)
187  self.sound_action.send_goal_and_wait(
188  SoundRequestGoal(sound_request=msg),
189  rospy.Duration(10.0))
190 
191  def df_run(self):
192  while True:
193  if rospy.is_shutdown():
194  break
195  try:
196  msg = self.queue.get(timeout=0.1)
197  rospy.loginfo("Processing")
198  if self.session_id is None:
199  self.session_id = str(uuid.uuid1())
200  rospy.loginfo(
201  "Created new session: {}".format(self.session_id))
202  session = self.session_client.session_path(
203  self.project_id, self.session_id)
204 
205  if isinstance(msg, AudioData):
206  result = self.detect_intent_audio(msg.data, session)
207  elif isinstance(msg, SpeechRecognitionCandidates):
208  result = self.detect_intent_text(
209  msg.transcript[0], session)
210  else:
211  raise RuntimeError("Invalid data")
212  self.print_result(result)
213  self.publish_result(result)
214  self.speak_result(result)
215  if result.action == "Bye":
216  self.state.set(State.IDLE)
217  self.session_id = None
218  except Queue.Empty:
219  pass
220  except Exception as e:
221  rospy.logerr(e)
222 
223 
224 if __name__ == '__main__':
225  rospy.init_node("dialogflow_client")
227  rospy.spin()
def __init__(self, init_state=None)
def detect_intent_text(self, data, session)
def detect_intent_audio(self, data, session)


dialogflow_task_executive
Author(s): Yuki Furuta
autogenerated on Tue May 11 2021 02:55:30