00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 import rospy
00036 import naoqi
00037
00038 from naoqi import (
00039 ALModule,
00040 ALBroker,
00041 ALProxy )
00042
00043 from naoqi_driver.naoqi_node import NaoqiNode
00044
00045 from std_msgs.msg import (
00046 String,
00047 Int32)
00048
00049 from std_srvs.srv import (
00050 EmptyResponse,
00051 Empty)
00052
00053 from nao_interaction_msgs.msg import (
00054 AudioSourceLocalization)
00055
00056 from nao_interaction_msgs.srv import (
00057 SetAudioMasterVolumeResponse,
00058 SetAudioMasterVolume,
00059 AudioRecorder,
00060 AudioPlayback)
00061
00062
00063 class Constants:
00064 NODE_NAME = "nao_audio_interface"
00065
00066 class NaoAudioInterface(ALModule, NaoqiNode):
00067 def __init__(self, moduleName):
00068
00069 NaoqiNode.__init__(self, Constants.NODE_NAME )
00070
00071
00072 self.ip = ""
00073 self.port = 10602
00074 self.moduleName = moduleName
00075 self.init_almodule()
00076
00077
00078 self.playFileSrv = rospy.Service("nao_audio/play_file", AudioPlayback, self.playFileSrv )
00079 self.masterVolumeSrv = rospy.Service("nao_audio/master_volume", SetAudioMasterVolume, self.handleAudioMasterVolumeSrv)
00080 self.enableRecordSrv = rospy.Service("nao_audio/record", AudioRecorder, self.handleRecorderSrv)
00081
00082 self.audioSourceLocalizationPub = rospy.Publisher("nao_audio/audio_source_localization", AudioSourceLocalization)
00083
00084 self.subscribe()
00085
00086 rospy.loginfo(Constants.NODE_NAME + " initialized")
00087
00088 def init_almodule(self):
00089
00090 rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport)
00091 try:
00092 self.broker = ALBroker("%sBroker" % self.moduleName, self.ip, self.port, self.pip, self.pport)
00093 except RuntimeError,e:
00094 print("Could not connect to NaoQi's main broker")
00095 exit(1)
00096 ALModule.__init__(self, self.moduleName)
00097
00098
00099 self.memProxy = ALProxy("ALMemory",self.pip,self.pport)
00100 if self.memProxy is None:
00101 rospy.logerr("Could not get a proxy to ALMemory on %s:%d", self.pip, self.pport)
00102 exit(1)
00103
00104 self.audioPlayerProxy = ALProxy("ALAudioPlayer",self.pip,self.pport)
00105 if self.audioPlayerProxy is None:
00106 rospy.logerr("Could not get a proxy to ALAudioPlayer on %s:%d", self.pip, self.pport)
00107 exit(1)
00108
00109 self.audioRecorderProxy = ALProxy("ALAudioRecorder",self.pip,self.pport)
00110 if self.audioRecorderProxy is None:
00111 rospy.logerr("Could not get a proxy to ALAudioRecorder on %s:%d", self.pip, self.pport)
00112 exit(1)
00113
00114 self.audioDeviceProxy = ALProxy("ALAudioDevice",self.pip,self.pport)
00115 if self.audioDeviceProxy is None:
00116 rospy.logerr("Could not get a proxy to ALAudioDevice on %s:%d", self.pip, self.pport)
00117 exit(1)
00118
00119 self.audioSourceLocalizationProxy = ALProxy("ALAudioSourceLocalization",self.pip,self.pport)
00120 if self.audioSourceLocalizationProxy is None:
00121 rospy.logerr("Could not get a proxy to ALAudioSourceLocalization on %s:%d", self.pip, self.pport)
00122 exit(1)
00123
00124 self.audioSourceLocalizationProxy.setParameter("EnergyComputation", True)
00125 self.audioSourceLocalizationProxy.setParameter("Sensibility", 0.8)
00126
00127 def playFileSrv(self, req):
00128 "Serves the srv request for audio file playback"
00129
00130 if req.file_path.data == "":
00131 return EmptyResponse
00132
00133 self.audioPlayerProxy.playFile("/home/nao/" + req.file_path.data)
00134 return EmptyResponse
00135
00136 def handleAudioMasterVolumeSrv(self, req):
00137 if (req.master_volume.data < 0) or (req.master_volume.data > 100):
00138 return
00139
00140 self.audioDeviceProxy.setOutputVolume(req.master_volume.data)
00141 return SetAudioMasterVolumeResponse()
00142
00143 def handleRecorderSrv(self, req):
00144
00145 file_path = req.file_path.data
00146 if file_path == "":
00147 return EmptyResponse
00148
00149 secs = req.secs.data
00150 channels = []
00151
00152
00153 channels_enabled = 0
00154 if req.left_channel.data == True:
00155 channels.append(1)
00156 channels_enabled += 1
00157 else:
00158 channels.append(0)
00159
00160 if req.right_channel.data == True:
00161 channels.append(1)
00162 channels_enabled += 1
00163 else:
00164 channels.append(0)
00165
00166 if req.front_channel.data == True:
00167 channels.append(1)
00168 channels_enabled += 1
00169 else:
00170 channels.append(0)
00171
00172 if req.rear_channel.data == True:
00173 channels.append(1)
00174 channels_enabled += 1
00175 else:
00176 channels.append(0)
00177
00178
00179 if channels_enabled == 0:
00180 return EmptyResponse
00181
00182
00183 audio_type = ""
00184 if req.audio_type.data == 0:
00185 audio_type = "wav"
00186 elif req.audio_type.data == 1:
00187 audio_type = "ogg"
00188 else:
00189 return EmptyResponse
00190
00191
00192 samplerate = req.samplerate.data
00193 if samplerate <= 0:
00194 return EmptyResponse
00195
00196
00197 if (secs <= 0.0):
00198 return EmptyResponse
00199
00200 self.audioRecorderProxy.startMicrophonesRecording("/home/nao/" + file_path, audio_type, samplerate, channels)
00201 rospy.sleep(secs)
00202 self.audioRecorderProxy.stopMicrophonesRecording()
00203
00204 return EmptyResponse
00205
00206 def shutdown(self):
00207 self.unsubscribe()
00208
00209 def subscribe(self):
00210 self.memProxy.subscribeToEvent("ALAudioSourceLocalization/SoundLocated", self.moduleName, "onSoundLocated")
00211
00212 def unsubscribe(self):
00213 self.memProxy.unsubscribeToEvent("ALAudioSourceLocalization/SoundLocated", self.moduleName)
00214
00215 def onSoundLocated(self, strVarName, value, strMessage):
00216 msg = AudioSourceLocalization()
00217
00218 msg.azimuth.data = value[1][0]
00219 msg.elevation.data = value[1][1]
00220 msg.confidence.data = value[1][2]
00221 msg.energy.data = value[1][3]
00222
00223 msg.head_pose.position.x = value[2][0]
00224 msg.head_pose.position.y = value[2][1]
00225 msg.head_pose.position.z = value[2][2]
00226 msg.head_pose.orientation.x = value[2][3]
00227 msg.head_pose.orientation.y = value[2][4]
00228 msg.head_pose.orientation.z = value[2][5]
00229
00230 self.audioSourceLocalizationPub.publish(msg)
00231
00232
00233 if __name__ == '__main__':
00234
00235 ROSNaoAudioModule = NaoAudioInterface("ROSNaoAudioModule")
00236 rospy.spin()
00237 rospy.loginfo("Stopping ROSNaoAudioModule ...")
00238 ROSNaoAudioModule.shutdown();
00239 rospy.loginfo("ROSNaoAudioModule stopped.")
00240 exit(0)