#! /usr/bin/env python # import os # from time import sleep import rospy import actionlib # from naoqi import ALProxy from teleoperation.msg import RequestSpeechAction, RequestSpeechGoal from controller import inform_controller_factory in_progress = False state = 'idle' voc_state = { 'idle': 'start', 'imitate': 'stop' } _inform_controller = inform_controller_factory('speech') def done_cb(_, result): global in_progress, state rospy.loginfo(result) if result.word == 'start' and _inform_controller('imitate'): state = 'imitate' elif result.word == 'stop' and _inform_controller('stop'): state = 'idle' in_progress = False if __name__ == '__main__': rospy.init_node('speech_client') client = actionlib.SimpleActionClient('speech_server', RequestSpeechAction) client.wait_for_server() rospy.loginfo('SPEECH CLIENT: SERVER THERE') rospy.on_shutdown(lambda: client.cancel_goal()) while not rospy.is_shutdown(): if not _inform_controller('recognize'): if in_progress: client.cancel_goal() in_progress = False state = 'idle' continue if not in_progress: in_progress = True client.send_goal(RequestSpeechGoal([voc_state[state]]), done_cb) rospy.Rate(2).sleep()