mic_client.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 from google.cloud import speech
4 from google.cloud.speech import enums
5 from google.cloud.speech import types
6 import pyaudio
7 import Queue
8 import rospy
9 from std_msgs.msg import String
10 
11 
12 class GspeechClient(object):
13  def __init__(self):
14  # Audio stream input setup
15  FORMAT = pyaudio.paInt16
16  CHANNELS = 1
17  RATE = 16000
18  self.CHUNK = 4096
19  self.audio = pyaudio.PyAudio()
20  self.stream = self.audio.open(format=FORMAT, channels=CHANNELS,
21  rate=RATE, input=True,
22  frames_per_buffer=self.CHUNK,
23  stream_callback=self._get_data)
24  self._buff = Queue.Queue() # Buffer to hold audio data
25  self.closed = False
26 
27  # ROS Text Publisher
28  text_topic = rospy.get_param('/text_topic', '/dialogflow_text')
29  self.text_pub = rospy.Publisher(text_topic, String, queue_size=10)
30 
31  def _get_data(self, in_data, frame_count, time_info, status):
32  """Daemon thread to continuously get audio data from the server and put
33  it in a buffer.
34  """
35  # Uncomment this if you want to hear the audio being replayed.
36  self._buff.put(in_data)
37  return None, pyaudio.paContinue
38 
39  def _generator(self):
40  """Generator function that continuously yields audio chunks from the buffer.
41  Used to stream data to the Google Speech API Asynchronously.
42  """
43  while not self.closed:
44  # Check first chunk of data
45  chunk = self._buff.get()
46  if chunk is None:
47  return
48  data = [chunk]
49 
50  # Read in a stream till the end using a non-blocking get()
51  while True:
52  try:
53  chunk = self._buff.get(block=False)
54  if chunk is None:
55  return
56  data.append(chunk)
57  except Queue.Empty:
58  break
59 
60  yield b''.join(data)
61 
62  def _listen_print_loop(self, responses):
63  """Iterates through server responses and prints them.
64  The responses passed is a generator that will block until a response
65  is provided by the server.
66  Each response may contain multiple results, and each result may contain
67  multiple alternatives; for details, see https://goo.gl/tjCPAU. Here we
68  print only the transcription for the top alternative of the top result.
69  """
70  for response in responses:
71  # If not a valid response, move on to next potential one
72  if not response.results:
73  continue
74 
75  # The `results` list is consecutive. For streaming, we only care about
76  # the first result being considered, since once it's `is_final`, it
77  # moves on to considering the next utterance.
78  result = response.results[0]
79  if not result.alternatives:
80  continue
81 
82  # Display the transcription of the top alternative.
83  transcript = result.alternatives[0].transcript
84 
85  # Parse the final utterance
86  if result.is_final:
87  rospy.loginfo("Google Speech result: {}".format(result))
88  # Received data is Unicode, convert it to string
89  transcript = transcript.encode('utf-8')
90  # Strip the initial space, if any
91  if transcript.startswith(' '):
92  transcript = transcript[1:]
93  # Exit if needed
94  if transcript.lower() == 'exit':
95  self.shutdown()
96  # Send the rest of the sentence to topic
97  self.text_pub.publish(transcript)
98 
99  def gspeech_client(self):
100  """Creates the Google Speech API client, configures it, and sends/gets
101  audio/text data for parsing.
102  """
103  language_code = 'en-US'
104  client = speech.SpeechClient()
105  config = types.RecognitionConfig(
106  encoding=enums.RecognitionConfig.AudioEncoding.LINEAR16,
107  sample_rate_hertz=16000,
108  language_code=language_code)
109  streaming_config = types.StreamingRecognitionConfig(
110  config=config,
111  interim_results=True)
112  # Hack from Google Speech Python docs, very pythonic c:
113  requests = (types.StreamingRecognizeRequest(audio_content=content) for content in self._generator())
114  responses = client.streaming_recognize(streaming_config, requests)
115  self._listen_print_loop(responses)
116 
117  def shutdown(self):
118  """Shut down as cleanly as possible"""
119  rospy.loginfo("Shutting down")
120  self.closed = True
121  self._buff.put(None)
122  self.stream.close()
123  self.audio.terminate()
124  exit()
125 
126  def start_client(self):
127  """Entry function to start the client"""
128  try:
129  rospy.loginfo("Starting Google speech mic client")
130  self.gspeech_client()
131  except KeyboardInterrupt:
132  self.shutdown()
133 
134 
135 if __name__ == '__main__':
136  rospy.init_node('dialogflow_mic_client')
138  g.start_client()
139 
def _get_data(self, in_data, frame_count, time_info, status)
Definition: mic_client.py:31
def _listen_print_loop(self, responses)
Definition: mic_client.py:62


dialogflow_ros
Author(s): Anas Abou Allaban
autogenerated on Mon Jun 10 2019 13:02:59