8 import speech_recognition
as SR
9 except ImportError
as e:
10 raise ImportError(str(e) +
'\nplease try "pip install speechrecognition"')
12 from actionlib_msgs.msg
import GoalStatus, GoalStatusArray
13 from audio_common_msgs.msg
import AudioData
14 from sound_play.msg
import SoundRequest, SoundRequestAction, SoundRequestGoal
15 from speech_recognition_msgs.msg
import SpeechRecognitionCandidates
24 self.
language = rospy.get_param(
"~language",
"ja-JP")
29 rospy.get_param(
"~tts_tolerance", 1.0))
30 tts_action_names = rospy.get_param(
31 '~tts_action_names', [
'soundplay'])
40 for tts_action_name
in tts_action_names:
42 tts_action_name, SoundRequestAction)
43 if tts_action.wait_for_server(rospy.Duration(5.0)):
44 self.tts_actions.append(tts_action)
47 "action '{}' is not initialized." 48 .format(tts_action_name))
52 "speech_to_text", SpeechRecognitionCandidates, queue_size=1)
56 stamp = event.current_real
59 for st
in tts_action.action_client.last_status_msg.status_list:
60 if st.status == GoalStatus.ACTIVE:
67 rospy.logdebug(
"START CANCELLATION")
74 rospy.logdebug(
"END CANCELLATION")
79 rospy.loginfo(
"Speech is cancelled")
83 rospy.loginfo(
"Waiting for result %d" % len(data.get_raw_data()))
84 result = self.recognizer.recognize_google(
86 msg = SpeechRecognitionCandidates(transcript=[result])
87 self.pub_speech.publish(msg)
88 except SR.UnknownValueError
as e:
89 rospy.logerr(
"Failed to recognize: %s" % str(e))
90 except SR.RequestError
as e:
91 rospy.logerr(
"Failed to recognize: %s" % str(e))
94 if __name__ ==
'__main__':
95 rospy.init_node(
"speech_to_text")
def tts_timer_cb(self, event)