1
2
3 import threading;
4 import unittest;
5 import time;
6
7 from speakeasy.msg import SpeakEasyStatus;
8 from speakeasy.msg import SpeakEasyMusic, SpeakEasySound, SpeakEasyPlayhead, SpeakEasyTextToSpeech;
9
10 from music_player import TimeReference, PlayStatus;
11
12
13
14 try:
15 import roslib; roslib.load_manifest('speakeasy');
16 import rospy
17 ROS_IMPORT_OK = True;
18 except ImportError:
19
20 ROS_IMPORT_OK = False;
21
22
23 from utilities.speakeasy_utils import SpeakeasyUtils
24
25
29
37
44
45
47 '''
48 Provides all methods required to operate the SpeakEasy ROS node remotely.
49 Intention is for GUIs or other programs to use one instance of this class
50 to control all text-to-speech, sound effects, and music play functions if
51 those functions are provided by a SpeakEasy ROS node.
52 <p>
53 For an exmple to use if these three functions are provided locally, without
54 using ROS, see speakeasy_controller.py.
55 '''
56
57
58 STATUS_MSG_TIMEOUT = 5;
59
60
61
62
63
64
65 PLAYHEAD_MSG_TIMEOUT = 0.5;
66
67
69 '''
70 Initialize sound to play at the robot. Initializes
71 self.sound_file_names to a list of sound file names
72 for use with play-sound calls to the Robot via ROS.
73 @raise NotImplementedError: if ROS initialization failed.
74 @raise IOError: if SpeakEasy node is online, but service call to it failed.
75 '''
76
77 if not ROS_IMPORT_OK:
78 raise NotImplementedError("ROS is not installed on this machine.");
79
80 self.rosSpeakEasyNodeAvailable = False;
81 self.latestCapabilitiesReply = None;
82
83 self.nodeStatusLock = threading.Lock();
84 self.textToSpeechLock = threading.Lock();
85 self.musicLock = threading.Lock();
86 self.soundLock = threading.Lock();
87
88
89
90 self.speechThreads = [];
91 self.soundThreads = [];
92 self.musicThreads = [];
93
94
95
96
97
98 if not SpeakeasyUtils.processRunning('rosmaster'):
99 raise NotImplementedError("The roscore process is not running.");
100
101
102
103
104 self.rosSoundRequestor = rospy.Publisher('speakeasy_sound_req', SpeakEasySound);
105 self.rosMusicRequestor = rospy.Publisher('speakeasy_music_req', SpeakEasyMusic);
106 self.rosTTSRequestor = rospy.Publisher('speakeasy_text_to_speech_req', SpeakEasyTextToSpeech);
107
108
109
110
111 nodeInfo = rospy.init_node('speakeasy_remote_gui', anonymous=True);
112
113
114 rospy.sleep(1.0);
115
116
117 waitTime = 4;
118 secsWaited = 0;
119 while not self.robotAvailable() and (secsWaited < waitTime):
120 rospy.loginfo("No SpeakEasy node available. Keep checking for %d more second(s)..." % (waitTime - secsWaited));
121 rospy.sleep(1);
122 secsWaited += 1;
123 if secsWaited >= waitTime:
124 rospy.logerr("Speech/sound/music capabilities service is offline.");
125 self.rosSpeakEasyNodeAvailable = False;
126 raise NotImplementedError("Speech capabilities service is offline.");
127
128 rospy.loginfo("Speech capabilities service online.");
129
131 '''
132 Return True if a SpeakEasy service is available, i.e. if a SpeakEasy ROS
133 node is running. Else return False.
134 @return: Result of checking whether a live SpeakEasy node is detected.
135 @rtype: bool
136 '''
137 if self.getSpeakEasyNodeStatus() is None:
138 return False;
139 else:
140 return True;
141
143 '''
144 Return a SpeakEasy status message instance as received from a live
145 SpeakEasy node. See msg.SpeakEasyStatus.msg for field details.
146 @param cachedOK: Set True if OK to use a previously cached status message.
147 @type cachedOK: bool
148 @return: Message instance if available, else None. Message instances are unavailable if no SpeakEasy node is running.
149 @rtype: SpeakEasyStatus
150 '''
151 with self.nodeStatusLock:
152 if cachedOK and self.latestCapabilitiesReply is not None:
153 return self.latestCapabilitiesReply;
154 try:
155 self.latestCapabilitiesReply = rospy.wait_for_message('/speakeasy_status', SpeakEasyStatus, self.STATUS_MSG_TIMEOUT);
156 except rospy.ROSException:
157 rospy.loginfo("SpeakEasy status messages not being received.")
158 return None;
159 return self.latestCapabilitiesReply;
160
162 '''
163 Return a list of the sound effects that the SpeakEasy node is offering.
164 These effects may be invoked via the playSound() method.
165 @param cachedOK: Set True if OK to use a previously cached status message.
166 @type cachedOK: bool
167 @return: Array of sound effect names.
168 @rtype: [string]
169 '''
170 capabilities = self.getSpeakEasyNodeStatus(cachedOK=cachedOK);
171 if capabilities is not None:
172 return capabilities.sounds;
173 else:
174 return [];
175
177 '''
178 Return a list of the music files that the SpeakEasy node is offering.
179 These songs may be played via the playMusic() method.
180
181 @param cachedOK: Set True if OK to use a previously cached status message.
182 @type cachedOK: bool
183 @return: Array of music files.
184 @rtype: [bool]
185 '''
186 capabilities = self.getSpeakEasyNodeStatus(cachedOK=cachedOK);
187 if capabilities is not None:
188 return capabilities.music;
189 else:
190 return [];
191
192 - def getTextToSpeechEngineNames(self,cachedOK=False):
193 '''
194 Return array of text-to-speech engines that are available at the SpeakEasy node.
195 Examples: Festival, the Linux open source engine, or Cepstral, the commercial engine.
196 @param cachedOK: Set True if OK to use a previously cached status message.
197 @type cachedOK: bool
198 @return: List of engine names.
199 @rtype: [string]
200 '''
201 capabilities = self.getSpeakEasyNodeStatus(cachedOK=cachedOK);
202 if capabilities is not None:
203 return capabilities.ttsEngines;
204 else:
205 return [];
206
208 '''
209 Return a list of text-to-speech voices that the SpeakEasy node provides.
210 If a particular text-to-speech engine is specified, only that engine's
211 voices are returned, else all voices of all available engines are
212 returned in one list.
213 @param ttsEngine: Name of one available text-to-speech engine.
214 @type ttsEngine: string
215 @param cachedOK: Set True if OK to use a previously cached status message.
216 @type cachedOK: bool
217 @return: List of voice names, or empty list. List may be empty either because
218 the SpeakEasy node does not offer text-to-speech services, or because
219 the node has terminated, and is no longer broadcasting status messages.
220 @rtype: [string]
221 '''
222 capabilities = self.getSpeakEasyNodeStatus(cachedOK=cachedOK);
223 if capabilities is not None:
224 ttsVoicesEnums = capabilities.voices;
225 if ttsVoicesEnums == None:
226 return [];
227
228 voices = [];
229 for ttsEngineVoiceEnum in ttsVoicesEnums:
230 if ttsEngine is None or ttsEngineVoiceEnum.ttsEngine == ttsEngine:
231 voices.extend(ttsEngineVoiceEnum.voices);
232 return voices;
233 else:
234 return [];
235
237 '''
238 Return the number of simultaneous sound effects that the SpeakEasy node provides.
239 Note that SpeakEasy nodes can be configured to provide many sound effect channels,
240 though this API does not provide such control. Default is eight.
241 @param cachedOK: Set True if OK to use a previously cached status message.
242 @type cachedOK: bool
243 @return: Number of sound effect channels.
244 @rtype: int
245 '''
246 capabilities = self.getSpeakEasyNodeStatus(cachedOK=cachedOK);
247 if capabilities is not None:
248 return capabilities.numSoundChannels;
249 else:
250 return [];
251
253 '''
254 Return default sound effect volume level. Note that sound volume can be set
255 on a case-by-case basis in calls to playSound();
256 @param cachedOK: Set True if OK to use a previously cached status message.
257 @type cachedOK: bool
258 @return: Default sound volume as a number between 0.0 and 1.0.
259 @rtype: float
260 '''
261 capabilities = self.getSpeakEasyNodeStatus(cachedOK=cachedOK);
262 if capabilities is not None:
263 return capabilities.soundVolume;
264 else:
265 return [];
266
268 '''
269 Return default music volume level. Note that music volume can be set
270 on a case-by-case basis in calls to playMusic();
271 @param cachedOK: Set True if OK to use a previously cached status message.
272 @type cachedOK: bool
273 @return: Default sound volume as a number between 0.0 and 1.0.
274 @rtype: float
275 '''
276 capabilities = self.getSpeakEasyNodeStatus(cachedOK=cachedOK);
277 if capabilities is not None:
278 return capabilities.musicVolume;
279 else:
280 return [];
281
283 '''
284 Return current music play state. These states are defined in music_player.py.
285 For reference, at the time of this writing:
286 class PlayStatus:
287 - STOPPED = 0;
288 - PAUSED = 1;
289 - PLAYING = 2;
290 @param cachedOK: Set True if OK to use a previously cached status message.
291 @type cachedOK: bool
292 @return: Status of the music playback engine on the SpeakEasy node.
293 @rtype: PlayStatus
294 '''
295 capabilities = self.getSpeakEasyNodeStatus(cachedOK=cachedOK);
296 if capabilities is not None:
297 return capabilities.musicStatus;
298 else:
299 return [];
300
302 '''
303 Convenience method to determine whether music is currently either
304 playing or paused.
305 @return: True/False to indicate whether music status is currently PlayStatus.STOPPED.
306 @rtype: bool
307 '''
308 return self.getPlayStatus() != PlayStatus.STOPPED;
309
310 - def getTextToSpeechBusy(self, cachedOK=False):
311 '''
312 Return whether SpeakEasy node is currently generating speech from text.
313 @return: True/False to indicate whether text-to-speech engine is busy.
314 @rtype: bool
315 '''
316 capabilities = self.getSpeakEasyNodeStatus(cachedOK=cachedOK);
317 if capabilities is not None:
318 return capabilities.textToSpeechBusy;
319 else:
320 return False;
321
322
323
324 - def say(self, text, voice=None, ttsEngine=None, numRepeats=0, repeatPeriod=0, blockTillDone=False):
325 '''
326 Given a piece of text, generate corresponding speech at the SpeakEasy node site.
327 @param text: Words to speak.
328 @type text: string
329 @param voice: Name of text-to-speech voice to use.
330 @type voice: string
331 @param ttsEngine: Name of text-to-speech engine to use.
332 @type ttsEngine: string
333 @param numRepeats: Number of times the utterance is to be repeated after the first time. Use -1 if forever.
334 @type numRepeats: int
335 @param repeatPeriod: Time period in fractional seconds to wait between repeated utterances.
336 @type repeatPeriod: float
337 @param blockTillDone: Request to return immediately, or block until the utterance if finished.
338 @type blockTillDone: bool
339 @raises TypeError: if one of the parameters is of incorrect type.
340 '''
341
342 if not SpeakeasyUtils.ensureType(numRepeats, int):
343 raise TypeError("Number of repeats must be an integer. Was " + str(numRepeats));
344 if not SpeakeasyUtils.ensureType(repeatPeriod, int) and not SpeakeasyUtils.ensureType(repeatPeriod, float):
345 raise TypeError("Repeat period must be an integer or a float. Was " + str(repeatPeriod));
346
347 ttsRequestMsg = SpeakEasyTextToSpeech();
348 ttsRequestMsg.command = TTSCommands.SAY;
349 ttsRequestMsg.text = text;
350 if voice is not None:
351 ttsRequestMsg.voiceName = voice;
352 else:
353 ttsRequestMsg.voiceName = '';
354 if ttsEngine is not None:
355 ttsRequestMsg.engineName = ttsEngine;
356 else:
357 ttsRequestMsg.engineName = '';
358
359 with self.textToSpeechLock:
360 self.rosTTSRequestor.publish(ttsRequestMsg);
361
362
363
364 if numRepeats > 0 or numRepeats == -1:
365 speechRepeatThread = RoboComm.SpeechReplayDemon(text, voice, ttsEngine, numRepeats, repeatPeriod, self);
366 self.registerSpeechRepeaterThread(speechRepeatThread);
367 speechRepeatThread.start();
368
369 if blockTillDone:
370 while self.getTextToSpeechBusy():
371 rospy.sleep(0.5);
372
374 '''
375 Stop text-to-speech utterance. No effect if text-to-speech is currently inactive.
376 '''
377 ttsRequestMsg = SpeakEasyTextToSpeech();
378 ttsRequestMsg.command = TTSCommands.STOP;
379 with self.textToSpeechLock:
380 self.rosTTSRequestor.publish(ttsRequestMsg);
381
382
383
384 self.killSpeechRepeatThreads(self.speechThreads);
385
386
387
388 - def playSound(self, soundName, volume=None, numRepeats=0, repeatPeriod=0):
389 '''
390 Play a sound effect at the SpeakEasy node.
391 @param soundName: Name of the sound effect. (see getSoundEffectNames()).
392 @type soundName: string
393 @param volume: Loudness for the sound effect. If None, current volume is used. Volume must be in range 0.0 to 1.0
394 @type volume: float.
395 @param numRepeats: Number of times the sound effect is to be repeated after the first time. Use -1 to play forever.
396 @type numRepeats: int
397 @param repeatPeriod: Time period in fractional seconds to wait between repeats.
398 @type repeatPeriod: float
399 @raise TypeError: if any parameter is of the wrong type.
400 '''
401
402 if not SpeakeasyUtils.ensureType(numRepeats, int):
403 raise TypeError("Number of repeats must be an integer. Was " + str(numRepeats));
404 if not SpeakeasyUtils.ensureType(repeatPeriod, int) and not SpeakeasyUtils.ensureType(repeatPeriod, float):
405 raise TypeError("Repeat period must be an integer or a float. Was " + str(repeatPeriod));
406
407 soundReqMsg = SpeakEasySound();
408 soundReqMsg.command = SoundCommands.PLAY;
409 soundReqMsg.sound_name = soundName;
410 if volume is None:
411 soundReqMsg.volume = -1.0;
412 else:
413 soundReqMsg.volume = volume;
414
415 with self.soundLock:
416 self.rosSoundRequestor.publish(soundReqMsg);
417
418
419
420 if numRepeats > 0 or numRepeats == -1:
421 soundRepeatThread = RoboComm.SoundReplayDemon(soundName, self, volume=volume, numRepeats=numRepeats, repeatPeriod=repeatPeriod);
422 self.registerSoundRepeaterThread(soundRepeatThread)
423 soundRepeatThread.start();
424
426 '''
427 Stop the all currently playing sound effects. Method has no effect if no sound is currently playing.
428 '''
429 soundReqMsg = SpeakEasySound();
430 soundReqMsg.command = SoundCommands.STOP;
431 with self.soundLock:
432 self.rosSoundRequestor.publish(soundReqMsg);
433
434
435
436 self.killSoundRepeatThreads(self.soundThreads);
437
439 '''
440 Pause the all currently playing sound effects. Method has no effect if no sound is currently playing.
441 '''
442 soundReqMsg = SpeakEasySound();
443 soundReqMsg.command = SoundCommands.PAUSE;
444 with self.soundLock:
445 self.rosSoundRequestor.publish(soundReqMsg);
446
448 '''
449 Un-pause all currently paused sound effects. Method has no effect if no sound is currently paused.
450 '''
451 soundReqMsg = SpeakEasySound();
452 soundReqMsg.command = SoundCommands.UNPAUSE;
453 with self.soundLock:
454 self.rosSoundRequestor.publish(soundReqMsg);
455
457 '''
458 Change the sound effect default volume.
459 @param volume: New default volume for sound effects. Value must be in range 0.0 to 1.0.
460 @type volume: float
461 @param soundName: Optionally the name of the sound whose volume is to be changed.
462 @type soundName: string
463 @raises TypeError: if any parameters are of incorrect type.
464 '''
465 if not SpeakeasyUtils.ensureType(volume, float):
466 raise TypeError("Volume must be a float between 0.0 and 1.0. Was " + str(volume));
467
468 soundReqMsg = SpeakEasySound();
469 soundReqMsg.command = SoundCommands.SET_VOL;
470 if soundName is None:
471 soundName = '';
472 soundReqMsg.sound_name = soundName;
473 soundReqMsg.volume = volume;
474 with self.soundLock:
475 self.rosSoundRequestor.publish(soundReqMsg);
476
477
478
480 '''
481 Play a piece of music (a sound file) at the SpeakEasy node.
482 @param songName: Name of sound file. (See getSongNames()).
483 @type songName: string
484 @param volume: Loudness at which to play. Default uses current volume. Else must be in range 0.0 to 1.0
485 @type volume: {None | float}
486 @param playheadTime: Offset in fractional seconds into where to start the song. Default: start at beginning.
487 @type playheadTime: float
488 @param timeReference: If playheadTime is provided, specifies whether the given time is intended as absolute (relative to the
489 beginning of the song), or relative to the current playhead position.
490 @type timeReference: TimeReference
491 @param numRepeats: Number of times the song is to be repeated after the first time. Use -1 to play forever.
492 @type numRepeats: int
493 @param repeatPeriod: Time period in fractional seconds to wait between repeats.
494 @type repeatPeriod: float
495 @raise TypeError: if any parameters are of incorrect type.
496 '''
497
498 if not SpeakeasyUtils.ensureType(numRepeats, int):
499 raise TypeError("Number of repeats must be an integer. Was " + str(numRepeats));
500 if not SpeakeasyUtils.ensureType(repeatPeriod, int) and not SpeakeasyUtils.ensureType(repeatPeriod, float):
501 raise TypeError("Repeat period must be an integer or a float. Was " + str(repeatPeriod));
502 if not SpeakeasyUtils.ensureType(playheadTime, int) and not SpeakeasyUtils.ensureType(playheadTime, float):
503 raise TypeError("Playhead must be an integer or a float. Was " + str(playheadTime));
504 if (timeReference != TimeReference.ABSOLUTE) and (timeReference != TimeReference.RELATIVE):
505 raise TypeError("Time reference must be TimeReference.RELATIVE, or TimeReference.ABSOLUTE. Was " + str(timeReference));
506
507 musicReqMsg = SpeakEasyMusic();
508 musicReqMsg.command = MusicCommands.PLAY;
509 musicReqMsg.song_name = songName;
510 musicReqMsg.time = playheadTime;
511 musicReqMsg.timeReference = timeReference;
512 if volume is None:
513 musicReqMsg.volume = -1.0;
514 else:
515 musicReqMsg.volume = volume;
516
517 with self.musicLock:
518 self.rosMusicRequestor.publish(musicReqMsg);
519
520
521
522 if numRepeats > 0 or numRepeats == -1:
523 musicRepeatThread = RoboComm.MusicReplayDemon(songName, volume, playheadTime, timeReference, numRepeats, repeatPeriod, self);
524 self.registerMusicRepeaterThread(musicRepeatThread);
525 musicRepeatThread.start();
526
528 '''
529 Stop currently playing music. No effect if nothing playing.
530 '''
531 musicReqMsg = SpeakEasyMusic();
532 musicReqMsg.command = MusicCommands.STOP;
533 with self.musicLock:
534 self.rosMusicRequestor.publish(musicReqMsg);
535
536
537
538 self.killMusicRepeatThreads(self.musicThreads);
539
541 '''
542 Pause currently playing music. No effect if nothing playing.
543 '''
544 musicReqMsg = SpeakEasyMusic();
545 musicReqMsg.command = MusicCommands.PAUSE;
546 with self.musicLock:
547 self.rosMusicRequestor.publish(musicReqMsg);
548
550 '''
551 Un-pause currently playing music. No effect if nothing paused or playing.
552 '''
553 musicReqMsg = SpeakEasyMusic();
554 musicReqMsg.command = MusicCommands.UNPAUSE;
555 with self.musicLock:
556 self.rosMusicRequestor.publish(musicReqMsg);
557
559 '''
560 Set default volume of music playback.
561 @param vol: Loudness value between 0.0 and 1.0.
562 @type vol: float
563 @raise TypeError: if any parameters are of incorrect type.
564 '''
565 if not SpeakeasyUtils.ensureType(vol, float):
566 raise TypeError("Volume must be a float between 0.0 and 1.0. Was " + str(vol));
567
568 musicReqMsg = SpeakEasyMusic();
569 musicReqMsg.command = MusicCommands.SET_VOL;
570 musicReqMsg.volume = vol;
571 with self.musicLock:
572 self.rosMusicRequestor.publish(musicReqMsg);
573
575 '''
576 Change the music playhead position to a particular time within a song.
577 Time may be specified absolute (i.e. relative to the start of the song),
578 or relative to the current playhead. The playhead may be changed during
579 playback, or while a song is paused.
580 @param playheadTime: New time where to position the playhead.
581 @type playheadTime: float
582 @param timeReference: TimeReference.ABSOLUTE or TimeReference.RELATIVE
583 @type timeReference: TimeReference.
584 @raise TypeError: if any parameters are of incorrect type.
585 '''
586 if not SpeakeasyUtils.ensureType(playheadTime, int) and not SpeakeasyUtils.ensureType(playheadTime, float):
587 raise TypeError("Playhead must be an int or float indicating seconds. Was " + str(playheadTime));
588
589 musicReqMsg = SpeakEasyMusic();
590 musicReqMsg.command = MusicCommands.SET_PLAYHEAD;
591 musicReqMsg.time = playheadTime;
592 musicReqMsg.timeReference = timeReference;
593 with self.musicLock:
594 self.rosMusicRequestor.publish(musicReqMsg);
595
597 '''
598 Return song position in fractional seconds. Return None
599 if no music is currently playing.
600 @return: Position in fractional seconds.
601 @rtype: float
602 '''
603 try:
604 playHeadMsg = rospy.wait_for_message('/speakeasy_playhead', SpeakEasyPlayhead, self.PLAYHEAD_MSG_TIMEOUT);
605 return playHeadMsg.playhead_time;
606 except:
607 return None;
608
609
610
611
612
613
614
615
616
617
619 with self.textToSpeechLock:
620 self.speechThreads.append(speechThread);
621
623
624
625 for speechThread in list(speechThreads):
626 speechThread.stop();
627
629 with self.soundLock:
630 self.soundThreads.append(soundThread);
631
633
634
635 for soundThread in list(soundThreads):
636 soundThread.stop();
637
639 with self.musicLock:
640 self.musicThreads.append(musicThread);
641
643
644
645 for musicThread in list(musicThreads):
646 musicThread.stop();
647
649
650 try:
651 threadList.remove(threadObj);
652 except:
653 pass;
654
655
656
658 '''
659 Abstract class of all repeat demons: text-to-speech, sound effects, and music.
660 '''
661
663 super(RoboComm.ReplayDemon, self).__init__();
664
665
666
667 self.daemon = True;
668
669 self.repeatPeriod = repeatPeriod;
670 self.stopped = True;
671
673 '''
674 Set this thread's name to nameRoot plus time-and-date.
675 @param nameRoot: Prefix of the thread name. E.g. "speechRepeatThread'
676 @type nameRoot: string
677 '''
678
679 timeStr = time.strftime("%a_%b_%d_%H:%M")
680
681 name = nameRoot + "_" + timeStr;
682 self.name = name;
683
685 '''
686 Responsible for repeating sound effects at appropriate intervals. Runs as thread.
687 '''
688
689 - def __init__(self, soundName, roboComm, volume=None, numRepeats=0, repeatPeriod=0):
690 super(RoboComm.SoundReplayDemon, self).__init__(repeatPeriod);
691 self.setName("soundReplayThread");
692
693 self.soundName = soundName;
694 self.volume = volume;
695 self.numRepeats = numRepeats;
696 if numRepeats == -1:
697 self.playForever = True;
698 else:
699 self.playForever = False;
700 self.roboComm = roboComm;
701
703
704
705
706 try:
707 import pydevd
708 pydevd.connected = True
709 pydevd.settrace(suspend=False)
710 except:
711 pass;
712
713 self.stopped = False;
714 while not self.stopped and ((self.numRepeats > 0) or self.playForever):
715
716
717 time.sleep(self.repeatPeriod);
718 self.roboComm.playSound(self.soundName, volume=self.volume)
719 if not self.playForever:
720 self.numRepeats -= 1;
721
722 with self.roboComm.soundLock:
723 self.roboComm.unregisterRepeatThread(self, self.roboComm.soundThreads);
724
726 self.stopped = True;
727 with self.roboComm.soundLock:
728 self.roboComm.unregisterRepeatThread(self, self.roboComm.soundThreads);
729
731 '''
732 Responsible for repeating songs at appropriate intervals. Runs as thread.
733 '''
734
736 super(RoboComm.SoundReplayDemon, self).__init__(repeatPeriod);
737 self.setName("musicReplayThread");
738
739 self.songName = songName
740 self.roboComm = roboComm
741 self.volume = volume
742 self.playhead = playhead
743 self.timeReference = timeReference
744 self.numRepeats = numRepeats
745 if numRepeats == -1:
746 self.playForever = True;
747 else:
748 self.playForever = False;
749
750 self.repeatPeriod = repeatPeriod
751
753
754
755
756 try:
757 import pydevd
758 pydevd.connected = True
759 pydevd.settrace(suspend=False)
760 except:
761 pass;
762
763 self.stopped = False;
764 while not self.stopped and ((self.numRepeats > 0) or self.playForever):
765
766
767 time.sleep(self.repeatPeriod);
768 self.roboComm.playMusic(self.songName,
769 volume=self.volume,
770 playhead=self.playhead,
771 timeReference=self.timeReference);
772 if not self.playForever:
773 self.numRepeats -= 1;
774
775 with self.roboComm.musicLock:
776 self.roboComm.unregisterRepeatThread(self, self.roboComm.musicThreads);
777
779 self.stopped = True;
780 with self.roboComm.musicLock:
781 self.roboComm.unregisterRepeatThread(self, self.roboComm.musicThreads);
782
784 '''
785 Responsible for repeating text-to-speech utterances at appropriate intervals. Runs as thread.
786 '''
787
788 - def __init__(self, text, voiceName, ttsEngine, numRepeats, repeatPeriod, roboComm):
789 super(RoboComm.SpeechReplayDemon, self).__init__(repeatPeriod);
790 self.setName("speechReplayThread");
791
792 self.text = text;
793 self.voiceName = voiceName;
794 self.ttsEngine = ttsEngine;
795 if numRepeats == -1:
796 self.playForever = True;
797 else:
798 self.playForever = False;
799 self.numRepeats = numRepeats;
800 self.roboComm = roboComm;
801
803
804
805
806 try:
807 import pydevd
808 pydevd.connected = True
809 pydevd.settrace(suspend=False)
810 except:
811 pass;
812
813 self.stopped = False;
814 while self.roboComm.getTextToSpeechBusy():
815
816
817 time.sleep(0.5);
818 while not self.stopped and ((self.numRepeats > 0) or self.playForever):
819
820
821 time.sleep(self.repeatPeriod);
822 self.roboComm.say(self.text, voice=self.voiceName, ttsEngine=self.ttsEngine, blockTillDone=True);
823 if not self.playForever:
824 self.numRepeats -= 1;
825
826 with self.roboComm.textToSpeechLock:
827 self.roboComm.unregisterRepeatThread(self, self.roboComm.speechThreads);
828
830 self.stopped = True;
831 with self.roboComm.textToSpeechLock:
832 self.roboComm.unregisterRepeatThread(self, self.roboComm.speechThreads);
833
834
835
842
843 groupsToTest = [TestGroup.STATUS_MSGS];
844
845
847
849 unittest.TestCase.setUp(self);
850 try:
851 self.roboComm = RoboComm();
852 except Exception as e:
853 print "ROS SpeakEasy service not available. No tests run: %s" %e
854 import sys;
855 sys.exit();
856
859
860
862 import math;
863 self.assertEqual(math.ceil(self.roboComm.getMusicVolume()), 1.0, "Get music volume failed.");
864 self.assertEqual(math.ceil(self.roboComm.getSoundVolume()), 1.0, "Get music volume failed.");
865
866
868 self.assertEqual(self.roboComm.getPlayStatus(), 0, "Play status is not 'stopped'");
869
870
872 self.assertEqual(self.roboComm.getNumSoundChannels(cachedOK=True), 8, "Wrong number of sound channels.");
873
874
876 self.assertIn('voice_kal_diphone', self.roboComm.getVoiceNames('festival',cachedOK=True), "Festival engine not reported to contain 'voice_kal_diphone'");
877 self.assertIn('festival', self.roboComm.getTextToSpeechEngineNames(), "Festival engine not reported as present.");
878
879
881 self.assertIn('cottonFields.ogg', self.roboComm.getSongNames(), "Cottonfields not reported as present in available music.");
882 self.assertIn('drill.wav', self.roboComm.getSoundEffectNames(), "Drill.wav not reported as present in sounds.");
883
884
886 self.roboComm.say("This is a test.");
887 rospy.spin();
888
889 if __name__ == '__main__':
890
891
892 try:
893 roboComm = RoboComm();
894 except NotImplementedError:
895 rospy.logerr("You must start a SpeakEasy service first.");
896 import sys
897 sys.exit();
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960 rospy.loginfo("Done testing robot_interaction.py")
961