nao_audio.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 #
00004 # ROS node to serve NAOqi audio functionalities
00005 # This code is currently compatible to NaoQI version 1.6
00006 #
00007 # Copyright 2014 Manos Tsardoulias, CERTH/ITI
00008 # http://www.ros.org/wiki/nao
00009 #
00010 # Redistribution and use in source and binary forms, with or without
00011 # modification, are permitted provided that the following conditions are met:
00012 #
00013 #    # Redistributions of source code must retain the above copyright
00014 #       notice, this list of conditions and the following disclaimer.
00015 #    # Redistributions in binary form must reproduce the above copyright
00016 #       notice, this list of conditions and the following disclaimer in the
00017 #       documentation and/or other materials provided with the distribution.
00018 #    # Neither the name of the CERTH/ITI nor the names of its
00019 #       contributors may be used to endorse or promote products derived from
00020 #       this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00023 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00024 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00025 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00026 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00027 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00028 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00029 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00030 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00031 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
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     AudioMasterVolume,
00058     AudioRecorder,
00059     AudioPlayback)
00060 
00061 
00062 class Constants:
00063     NODE_NAME = "nao_audio_interface"
00064 
00065 class NaoAudioInterface(ALModule, NaoqiNode):
00066     def __init__(self, moduleName):
00067         # ROS initialization
00068         NaoqiNode.__init__(self, Constants.NODE_NAME )
00069         
00070         # NAOQi initialization
00071         self.ip = ""
00072         self.port = 10602
00073         self.moduleName = moduleName
00074         self.init_almodule()
00075         
00076         #~ ROS initializations
00077         self.playFileSrv = rospy.Service("nao_audio/play_file", AudioPlayback, self.playFileSrv )        
00078         self.masterVolumeSrv = rospy.Service("nao_audio/master_volume", AudioMasterVolume, self.handleAudioMasterVolumeSrv)
00079         self.enableRecordSrv = rospy.Service("nao_audio/record", AudioRecorder, self.handleRecorderSrv)
00080         
00081         self.audioSourceLocalizationPub = rospy.Publisher("nao_audio/audio_source_localization", AudioSourceLocalization)
00082         
00083         self.subscribe()
00084         
00085         rospy.loginfo(Constants.NODE_NAME + " initialized")
00086   
00087     def init_almodule(self):
00088         # before we can instantiate an ALModule, an ALBroker has to be created
00089         rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport)
00090         try:
00091             self.broker = ALBroker("%sBroker" % self.moduleName, self.ip, self.port, self.pip, self.pport)
00092         except RuntimeError,e:
00093             print("Could not connect to NaoQi's main broker")
00094             exit(1)
00095         ALModule.__init__(self, self.moduleName)
00096         
00097         #~ Memory proxy registration
00098         self.memProxy = ALProxy("ALMemory",self.pip,self.pport)
00099         if self.memProxy is None:
00100             rospy.logerror("Could not get a proxy to ALMemory on %s:%d", self.pip, self.pport)
00101             exit(1)
00102         #~ ALAudioProxy registration
00103         self.audioPlayerProxy = ALProxy("ALAudioPlayer",self.pip,self.pport)
00104         if self.audioPlayerProxy is None:
00105             rospy.logerror("Could not get a proxy to ALAudioPlayer on %s:%d", self.pip, self.pport)
00106             exit(1)
00107         #~ ALAudioRecorder proxy registration 
00108         self.audioRecorderProxy = ALProxy("ALAudioRecorder",self.pip,self.pport)
00109         if self.audioRecorderProxy is None:
00110             rospy.logerror("Could not get a proxy to ALAudioRecorder on %s:%d", self.pip, self.pport)
00111             exit(1)
00112         #~ ALAudioDevice proxy registration
00113         self.audioDeviceProxy = ALProxy("ALAudioDevice",self.pip,self.pport)
00114         if self.audioDeviceProxy is None:
00115             rospy.logerror("Could not get a proxy to ALAudioDevice on %s:%d", self.pip, self.pport)
00116             exit(1)
00117         #~ ALAudioSourceLocalization registration 
00118         self.audioSourceLocalizationProxy = ALProxy("ALAudioSourceLocalization",self.pip,self.pport)
00119         if self.audioSourceLocalizationProxy is None:
00120             rospy.logerror("Could not get a proxy to ALAudioSourceLocalization on %s:%d", self.pip, self.pport)
00121             exit(1)
00122         #~ ALAudioSourceLocalization parameter trimming
00123         self.audioSourceLocalizationProxy.setParameter("EnergyComputation", True)
00124         self.audioSourceLocalizationProxy.setParameter("Sensibility", 0.8)
00125 
00126     def playFileSrv(self, req):
00127         "Serves the srv request for audio file playback"
00128         
00129         if req.file_path.data == "":
00130             return EmptyResponse
00131         
00132         self.audioPlayerProxy.playFile("/home/nao/" + req.file_path.data)
00133         return EmptyResponse
00134         
00135     def handleAudioMasterVolumeSrv(self, req):
00136         if (req.master_volume.data < 0) or (req.master_volume.data > 100):
00137             return EmptyResponse
00138         
00139         self.audioDeviceProxy.setOutputVolume(req.master_volume.data)
00140         return EmptyResponse
00141     
00142     def handleRecorderSrv(self, req):
00143         
00144         file_path = req.file_path.data
00145         if file_path == "":
00146             return EmptyResponse
00147             
00148         secs = req.secs.data
00149         channels = []
00150         
00151         #~ Channel setup
00152         channels_enabled = 0
00153         if req.left_channel.data == True:
00154             channels.append(1)
00155             channels_enabled += 1
00156         else:
00157             channels.append(0)
00158             
00159         if req.right_channel.data == True:
00160             channels.append(1)
00161             channels_enabled += 1
00162         else:
00163             channels.append(0)
00164             
00165         if req.front_channel.data == True:
00166             channels.append(1)
00167             channels_enabled += 1
00168         else:
00169             channels.append(0)
00170             
00171         if req.rear_channel.data == True:
00172             channels.append(1)
00173             channels_enabled += 1
00174         else:
00175             channels.append(0)
00176        
00177         #~ If no channels were selected return
00178         if channels_enabled == 0:
00179             return EmptyResponse
00180         
00181         #~ Set audio type
00182         audio_type = ""
00183         if req.audio_type.data == 0:
00184             audio_type = "wav"
00185         elif req.audio_type.data == 1:
00186             audio_type = "ogg"
00187         else:
00188             return EmptyResponse
00189         
00190         #~ Set samplerate    
00191         samplerate = req.samplerate.data
00192         if samplerate <= 0:
00193             return EmptyResponse
00194         
00195         #~ Set recording type 
00196         if (secs <= 0.0):
00197             return EmptyResponse
00198 
00199         self.audioRecorderProxy.startMicrophonesRecording("/home/nao/" + file_path, audio_type, samplerate, channels)
00200         rospy.sleep(secs)        
00201         self.audioRecorderProxy.stopMicrophonesRecording()
00202         
00203         return EmptyResponse
00204     
00205     def shutdown(self): 
00206         self.unsubscribe()
00207 
00208     def subscribe(self):
00209         self.memProxy.subscribeToEvent("ALAudioSourceLocalization/SoundLocated", self.moduleName, "onSoundLocated")
00210 
00211     def unsubscribe(self):
00212         self.memProxy.unsubscribeToEvent("ALAudioSourceLocalization/SoundLocated", self.moduleName)
00213         
00214     def onSoundLocated(self, strVarName, value, strMessage):
00215         msg = AudioSourceLocalization()
00216         
00217         msg.azimuth.data = value[1][0]
00218         msg.elevation.data = value[1][1]
00219         msg.confidence.data = value[1][2]
00220         msg.energy.data = value[1][3]
00221         
00222         msg.head_pose.position.x = value[2][0]
00223         msg.head_pose.position.y = value[2][1]
00224         msg.head_pose.position.z = value[2][2]
00225         msg.head_pose.orientation.x = value[2][3]
00226         msg.head_pose.orientation.y = value[2][4]
00227         msg.head_pose.orientation.z = value[2][5]
00228         
00229         self.audioSourceLocalizationPub.publish(msg)
00230         
00231 
00232 if __name__ == '__main__':
00233   
00234     ROSNaoAudioModule = NaoAudioInterface("ROSNaoAudioModule")
00235     rospy.spin()
00236     rospy.loginfo("Stopping ROSNaoAudioModule ...")
00237     ROSNaoAudioModule.shutdown();        
00238     rospy.loginfo("ROSNaoAudioModule stopped.")
00239     exit(0)


nao_audio
Author(s): Manos Tsardoulias
autogenerated on Thu Aug 27 2015 14:02:39