def say(self, text, voice=None, ttsEngine=None, numRepeats=0, repeatPeriod=0, blockTillDone=False): ''' Given a piece of text, generate corresponding speech at the SpeakEasy node site. @param text: Words to speak. @type text: string @param voice: Name of text-to-speech voice to use. @type voice: string @param ttsEngine: Name of text-to-speech engine to use. @type ttsEngine: string @param numRepeats: Number of times the utterance is to be repeated after the first time. Use -1 if forever. @type numRepeats: int @param repeatPeriod: Time period in fractional seconds to wait between repeated utterances. @type repeatPeriod: float @param blockTillDone: Request to return immediately, or block until the utterance if finished. @type blockTillDone: bool @raises TypeError: if one of the parameters is of incorrect type. ''' if not SpeakeasyUtils.ensureType(numRepeats, int): raise TypeError("Number of repeats must be an integer. Was " + str(numRepeats)); if not SpeakeasyUtils.ensureType(repeatPeriod, int) and not SpeakeasyUtils.ensureType(repeatPeriod, float): raise TypeError("Repeat period must be an integer or a float. Was " + str(repeatPeriod)); ttsRequestMsg = SpeakEasyTextToSpeech(); ttsRequestMsg.command = TTSCommands.SAY; ttsRequestMsg.text = text; if voice is not None: ttsRequestMsg.voiceName = voice; else: ttsRequestMsg.voiceName = ''; if ttsEngine is not None: ttsRequestMsg.engineName = ttsEngine; else: ttsRequestMsg.engineName = ''; with self.textToSpeechLock: self.rosTTSRequestor.publish(ttsRequestMsg); # Keep this block out of the lock! Thread registration will # acquire the lock (thus leading to deadlock, if lock is owned here): if numRepeats > 0 or numRepeats == -1: speechRepeatThread = RoboComm.SpeechReplayDemon(text, voice, ttsEngine, numRepeats, repeatPeriod, self); self.registerSpeechRepeaterThread(speechRepeatThread); speechRepeatThread.start(); if blockTillDone: while self.getTextToSpeechBusy(): rospy.sleep(0.5);
def playMusic(self, songName, volume=None, playheadTime=0.0, timeReference=TimeReference.ABSOLUTE, numRepeats=0, repeatPeriod=0): ''' Play a piece of music (a sound file) at the SpeakEasy node. @param songName: Name of sound file. (See getSongNames()). @type songName: string @param volume: Loudness at which to play. Default uses current volume. Else must be in range 0.0 to 1.0 @type volume: {None | float} @param playheadTime: Offset in fractional seconds into where to start the song. Default: start at beginning. @type playheadTime: float @param timeReference: If playheadTime is provided, specifies whether the given time is intended as absolute (relative to the beginning of the song), or relative to the current playhead position. @type timeReference: TimeReference @param numRepeats: Number of times the song is to be repeated after the first time. Use -1 to play forever. @type numRepeats: int @param repeatPeriod: Time period in fractional seconds to wait between repeats. @type repeatPeriod: float @raise TypeError: if any parameters are of incorrect type. ''' if not SpeakeasyUtils.ensureType(numRepeats, int): raise TypeError("Number of repeats must be an integer. Was " + str(numRepeats)); if not SpeakeasyUtils.ensureType(repeatPeriod, int) and not SpeakeasyUtils.ensureType(repeatPeriod, float): raise TypeError("Repeat period must be an integer or a float. Was " + str(repeatPeriod)); if not SpeakeasyUtils.ensureType(playheadTime, int) and not SpeakeasyUtils.ensureType(playheadTime, float): raise TypeError("Playhead must be an integer or a float. Was " + str(playheadTime)); if (timeReference != TimeReference.ABSOLUTE) and (timeReference != TimeReference.RELATIVE): raise TypeError("Time reference must be TimeReference.RELATIVE, or TimeReference.ABSOLUTE. Was " + str(timeReference)); musicReqMsg = SpeakEasyMusic(); musicReqMsg.command = MusicCommands.PLAY; musicReqMsg.song_name = songName; musicReqMsg.time = playheadTime; musicReqMsg.timeReference = timeReference; if volume is None: musicReqMsg.volume = -1.0; else: musicReqMsg.volume = volume; with self.musicLock: self.rosMusicRequestor.publish(musicReqMsg); # Keep this block out of the lock! Thread registration will # acquire the lock (thus leading to deadlock, if lock is owned here): if numRepeats > 0 or numRepeats == -1: musicRepeatThread = RoboComm.MusicReplayDemon(songName, volume, playheadTime, timeReference, numRepeats, repeatPeriod, self); self.registerMusicRepeaterThread(musicRepeatThread); musicRepeatThread.start();
def setPlayhead(self, playheadTime, timeReference=TimeReference.ABSOLUTE): ''' Change the music playhead position to a particular time within a song. Time may be specified absolute (i.e. relative to the start of the song), or relative to the current playhead. The playhead may be changed during playback, or while a song is paused. @param playheadTime: New time where to position the playhead. @type playheadTime: float @param timeReference: TimeReference.ABSOLUTE or TimeReference.RELATIVE @type timeReference: TimeReference. @raise TypeError: if any parameters are of incorrect type. ''' if not SpeakeasyUtils.ensureType(playheadTime, int) and not SpeakeasyUtils.ensureType(playheadTime, float): raise TypeError("Playhead must be an int or float indicating seconds. Was " + str(playheadTime)); musicReqMsg = SpeakEasyMusic(); musicReqMsg.command = MusicCommands.SET_PLAYHEAD; musicReqMsg.time = playheadTime; musicReqMsg.timeReference = timeReference; with self.musicLock: self.rosMusicRequestor.publish(musicReqMsg);
def setMusicVolume(self, vol): ''' Set default volume of music playback. @param vol: Loudness value between 0.0 and 1.0. @type vol: float @raise TypeError: if any parameters are of incorrect type. ''' if not SpeakeasyUtils.ensureType(vol, float): raise TypeError("Volume must be a float between 0.0 and 1.0. Was " + str(vol)); musicReqMsg = SpeakEasyMusic(); musicReqMsg.command = MusicCommands.SET_VOL; musicReqMsg.volume = vol; with self.musicLock: self.rosMusicRequestor.publish(musicReqMsg);
def playSound(self, soundName, volume=None, numRepeats=0, repeatPeriod=0): ''' Play a sound effect at the SpeakEasy node. @param soundName: Name of the sound effect. (see getSoundEffectNames()). @type soundName: string @param volume: Loudness for the sound effect. If None, current volume is used. Volume must be in range 0.0 to 1.0 @type volume: float. @param numRepeats: Number of times the sound effect is to be repeated after the first time. Use -1 to play forever. @type numRepeats: int @param repeatPeriod: Time period in fractional seconds to wait between repeats. @type repeatPeriod: float @raise TypeError: if any parameter is of the wrong type. ''' if not SpeakeasyUtils.ensureType(numRepeats, int): raise TypeError("Number of repeats must be an integer. Was " + str(numRepeats)); if not SpeakeasyUtils.ensureType(repeatPeriod, int) and not SpeakeasyUtils.ensureType(repeatPeriod, float): raise TypeError("Repeat period must be an integer or a float. Was " + str(repeatPeriod)); soundReqMsg = SpeakEasySound(); soundReqMsg.command = SoundCommands.PLAY; soundReqMsg.sound_name = soundName; if volume is None: soundReqMsg.volume = -1.0; else: soundReqMsg.volume = volume; with self.soundLock: self.rosSoundRequestor.publish(soundReqMsg); # Keep this block out of the lock! Thread registration will # acquire the lock (thus leading to deadlock, if lock is owned here): if numRepeats > 0 or numRepeats == -1: soundRepeatThread = RoboComm.SoundReplayDemon(soundName, self, volume=volume, numRepeats=numRepeats, repeatPeriod=repeatPeriod); self.registerSoundRepeaterThread(soundRepeatThread) soundRepeatThread.start();
def setSoundVolume(self, volume, soundName=None): ''' Change the sound effect default volume. @param volume: New default volume for sound effects. Value must be in range 0.0 to 1.0. @type volume: float @param soundName: Optionally the name of the sound whose volume is to be changed. @type soundName: string @raises TypeError: if any parameters are of incorrect type. ''' if not SpeakeasyUtils.ensureType(volume, float): raise TypeError("Volume must be a float between 0.0 and 1.0. Was " + str(volume)); soundReqMsg = SpeakEasySound(); soundReqMsg.command = SoundCommands.SET_VOL; if soundName is None: soundName = ''; soundReqMsg.sound_name = soundName; soundReqMsg.volume = volume; with self.soundLock: self.rosSoundRequestor.publish(soundReqMsg);