Go to the documentation of this file.00001
00002
00003
00004
00005 try:
00006 import roslib; roslib.load_manifest('rospeex_core')
00007 except:
00008 pass
00009
00010 import rospy
00011 import traceback
00012
00013
00014 from rospeex_msgs.msg import SpeechRecognitionResponse
00015 from rospeex_msgs.msg import SpeechRecognitionRequest
00016
00017
00018 from rospeex_core.sr import SpeechRecognitionFactory
00019 from rospeex_core.exceptions import SpeechRecognitionException
00020 from rospeex_core.exceptions import ParameterException
00021 from rospeex_core.exceptions import ServerException
00022
00023 class SpeechRecognition(object):
00024 """ SpeechRecognition class """
00025
00026 _MY_NODE_NAME = 'rospeex_sr'
00027 _REQUEST_TOPIC_NAME = 'sr_req'
00028 _RESPONSE_TOPIC_NAME = 'sr_res'
00029
00030 def __init__(self):
00031 """ init """
00032 self._publisher = None
00033 self._user_request_dict = {}
00034
00035 def _update_user_dictionary(self, header):
00036 """ renew user request dictionary
00037 @param header: request header
00038 @type header: str
00039 """
00040 if self._user_request_dict.has_key(header.user):
00041 self._user_request_dict[header.user] += 1
00042 if int(header.request_id) != self._user_request_dict[header.user]:
00043
00044 rospy.logwarn('invalid request id. user:%s \
00045 current id:%d \
00046 previous id:%d'\
00047 %(header.user, \
00048 int(header.request_id), \
00049 self._user_request_dict[header.user]))
00050
00051 self._user_request_dict[header.user] = int(header.request_id)
00052 else:
00053 self._user_request_dict.update({header.user:int(header.request_id)})
00054 rospy.logdebug('add new user:%s' % header.user)
00055
00056
00057 def _callback_func(self, request):
00058 """ callback function for sr_req topic
00059 @param request: topic data
00060 @type request: str
00061 """
00062 rospy.loginfo(request)
00063 response = SpeechRecognitionResponse()
00064 response.header = request.header
00065
00066
00067 self._update_user_dictionary(request.header)
00068
00069
00070 try:
00071
00072 client = SpeechRecognitionFactory().create(engine=request.header.engine)
00073 response.message = client.request(request.data, request.header.language)
00074 except SpeechRecognitionException as err:
00075 rospy.logerr('[SpeechRecognitionException] ' + str(err))
00076 response.memo = str(err)
00077 except ParameterException as err:
00078 rospy.logerr('[ParameterException] ' + str(err))
00079 response.memo = str(err)
00080 except ServerException as err:
00081 rospy.logerr('[ServerException] ' + str(err))
00082 response.memo = str(err)
00083
00084
00085
00086 rospy.loginfo(response.header)
00087 self._publisher.publish(response)
00088
00089
00090 def run(self):
00091 """ run rospeex sr node """
00092 rospy.init_node(self._MY_NODE_NAME)
00093 rospy.Subscriber(self._REQUEST_TOPIC_NAME, SpeechRecognitionRequest, self._callback_func)
00094 self._publisher = rospy.Publisher(self._RESPONSE_TOPIC_NAME, SpeechRecognitionResponse)
00095 rospy.loginfo("start speech recognition node")
00096 rospy.spin()
00097
00098
00099 if __name__ == '__main__':
00100 try:
00101 node = SpeechRecognition()
00102 node.run()
00103 except rospy.ROSInterruptException:
00104 pass
00105 except Exception:
00106 rospy.logfatal(traceback.format_exc())
00107
00108
00109