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