Go to the documentation of this file.00001
00002 import array
00003 import collections
00004 import pyaudio
00005 import time
00006
00007 import rospy
00008 import gcloud_speech_msgs.msg as gcloud_speech_msgs
00009
00010 LinearPcm16Le16000Audio = gcloud_speech_msgs.LinearPcm16Le16000Audio
00011
00012 MSG_FRAME_PER_SLICE = 1600
00013
00014 _audio_queue = collections.deque()
00015
00016
00017 def RosCallback(msg):
00018 _audio_queue.append(msg.data)
00019 rospy.loginfo("Received {} bytes.".format(len(msg.data)))
00020
00021
00022 def PaCallback(in_data, frame_count, time_info, status):
00023 assert frame_count == MSG_FRAME_PER_SLICE * 2
00024
00025 while True:
00026 try:
00027
00028
00029
00030
00031 data_1 = _audio_queue.popleft()
00032 data_2 = _audio_queue.popleft()
00033 data = data_1 + data_2
00034 break
00035 except:
00036 time.sleep(1)
00037
00038 return (data, pyaudio.paContinue)
00039
00040
00041 def PlaybackMicrophoneAudio():
00042 rospy.init_node('playback_microphone_audio', anonymous=True)
00043 rospy.Subscriber(
00044 "/cogrob/microphone_audio", LinearPcm16Le16000Audio, RosCallback,
00045 queue_size=10)
00046 pa = pyaudio.PyAudio()
00047 stream = pa.open(
00048 format=pyaudio.paInt16, channels=1, rate=16000, output=True,
00049 stream_callback=PaCallback, frames_per_buffer=MSG_FRAME_PER_SLICE * 2)
00050
00051 stream.start_stream()
00052 rospy.spin()
00053 pa.terminate()
00054
00055
00056 if __name__ == '__main__':
00057 try:
00058 PlaybackMicrophoneAudio()
00059 except rospy.ROSInterruptException:
00060 pass