moved speech detection into controller
also the thing works quite good (as in demo-good)
This commit is contained in:
@@ -1,10 +1,44 @@
|
||||
#! /usr/bin/env python
|
||||
import rospy
|
||||
import actionlib
|
||||
|
||||
from teleoperation.srv import InformController, InformControllerResponse
|
||||
from teleoperation.msg import RequestSpeechAction, RequestSpeechGoal
|
||||
|
||||
|
||||
STATE = 'idle' # Also walk, imitate, fallen, recognizing
|
||||
STATE = 'dead' # Also walk, imitate, fallen, idle
|
||||
speech_in_progress = False
|
||||
|
||||
IMITATE = 'arms'
|
||||
KILL = 'kill'
|
||||
REVIVE = 'go'
|
||||
STOP = 'stop'
|
||||
|
||||
voc_state = {
|
||||
'idle': [IMITATE, KILL],
|
||||
'imitate': [STOP, KILL],
|
||||
'dead': [REVIVE]
|
||||
}
|
||||
|
||||
|
||||
def speech_done_cb(_, result):
|
||||
global speech_in_progress, STATE
|
||||
_state_old = STATE
|
||||
rospy.loginfo('SPEECH: {}'.format(result))
|
||||
if not result:
|
||||
speech_in_progress = False
|
||||
return
|
||||
if result.word == IMITATE and STATE == 'idle':
|
||||
STATE = 'imitate'
|
||||
elif result.word == STOP and STATE == 'imitate':
|
||||
STATE = 'idle'
|
||||
elif result.word == KILL and STATE in ('idle', 'imitate'):
|
||||
STATE = 'dead'
|
||||
elif result.word == REVIVE and STATE == 'dead':
|
||||
STATE = 'idle'
|
||||
if _state_old != STATE:
|
||||
rospy.loginfo('{} -> {}'.format(_state_old, STATE))
|
||||
speech_in_progress = False
|
||||
|
||||
|
||||
def inform_controller_factory(who):
|
||||
@@ -49,26 +83,6 @@ def handle_request(r):
|
||||
if STATE == 'imitate':
|
||||
permission = True
|
||||
|
||||
elif module == 'speech':
|
||||
if message == 'recognize':
|
||||
if STATE in ('idle', 'imitate', 'dead'):
|
||||
permission = True
|
||||
elif message == 'imitate':
|
||||
if STATE == 'idle':
|
||||
STATE = 'imitate'
|
||||
permission = True
|
||||
elif message == 'stop':
|
||||
if STATE == 'imitate':
|
||||
STATE = 'idle'
|
||||
permission = True
|
||||
elif message == 'kill':
|
||||
STATE = 'dead'
|
||||
permission = True
|
||||
elif message == 'revive':
|
||||
if STATE == 'dead':
|
||||
STATE = 'idle'
|
||||
permission = True
|
||||
|
||||
rospy.logdebug(
|
||||
'GOT REQUEST FROM %s TO %s.\nPERMISSION: %s.\nSTATE IS NOW: %s.' % (
|
||||
module, message, permission, STATE
|
||||
@@ -80,6 +94,25 @@ def handle_request(r):
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
rospy.init_node('controller', log_level=rospy.INFO)
|
||||
ic = rospy.Service('inform_controller', InformController, handle_request)
|
||||
rospy.spin()
|
||||
|
||||
client = actionlib.SimpleActionClient('speech_server',
|
||||
RequestSpeechAction)
|
||||
client.wait_for_server()
|
||||
rospy.loginfo('SPEECH: SERVER THERE')
|
||||
|
||||
rospy.on_shutdown(lambda: speech_in_progress and client.cancel_goal())
|
||||
|
||||
while not rospy.is_shutdown():
|
||||
if not STATE in ('idle', 'imitate', 'dead'):
|
||||
if speech_in_progress:
|
||||
client.cancel_goal()
|
||||
speech_in_progress = False
|
||||
else:
|
||||
if not speech_in_progress:
|
||||
speech_in_progress = True
|
||||
client.send_goal(RequestSpeechGoal(voc_state[STATE]),
|
||||
speech_done_cb)
|
||||
rospy.Rate(10).sleep()
|
||||
|
||||
Reference in New Issue
Block a user