Go to the documentation of this file.00001
00002
00003
00004 import rospy
00005 import threading
00006 import traceback
00007
00008
00009 from rospeex_core import logging_util
00010
00011
00012 from rospeex_msgs.msg import SpeechRecognitionResponse
00013 from rospeex_msgs.msg import SpeechRecognitionRequest
00014 from rospeex_msgs.msg import SignalProcessingStream
00015 from rospeex_msgs.srv import SpeechRecognitionConfig
00016
00017
00018 from rospeex_core import exceptions as ext
00019 from rospeex_core.sr import Factory
00020 from rospeex_core.sr import Engine
00021
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 _SPI_CONFIG_SERVICE_NAME = 'spi_config'
00030 _STREAM_TOPIC_NAME = 'spi_stream'
00031
00032 def __init__(self):
00033 """ init """
00034 self._publisher = None
00035 self._user_request_dict = {}
00036
00037
00038 self._stream_client = None
00039 self._stream_id = 0
00040 self._stream_engine = Engine.NICT
00041 self._stream_language = 'ja'
00042 self._sr_config_service = None
00043 self._stream_client_lock = threading.Lock()
00044
00045
00046 self._google_api_key = None
00047 self._microsoft_api_key = None
00048
00049 def _load_parameters(self):
00050 """ load paramters from roscore """
00051 self._google_api_key = rospy.get_param('~google_api_key', None)
00052 self._microsoft_api_key = rospy.get_param('~microsoft_api_key', None)
00053
00054 def _publish_streaming_result(self, text):
00055 """ publish streaming result data
00056 @param text: send text
00057 @type text: str
00058 """
00059 rospy.logdebug('SR result received')
00060 response = SpeechRecognitionResponse()
00061 response.header.engine = self._stream_engine
00062 response.header.language = self._stream_language
00063 response.header.user = 'spi'
00064 response.header.request_id = str(self._stream_id)
00065 response.message = text
00066 self._stream_id += 1
00067 self._publisher.publish(response)
00068
00069 def _update_user_dictionary(self, header):
00070 """ renew user request dictionary
00071 @param header: request header
00072 @type header: str
00073 """
00074 if header.user in self._user_request_dict:
00075 self._user_request_dict[header.user] += 1
00076 if int(header.request_id) != self._user_request_dict[header.user]:
00077
00078 msg = 'invalid request id. user:{} '\
00079 'current id:{}'\
00080 'previous id:{}'.format(
00081 header.user,
00082 int(header.request_id),
00083 self._user_request_dict[header.user]
00084 )
00085 rospy.logwarn(msg)
00086
00087
00088 self._user_request_dict[header.user] = int(header.request_id)
00089
00090 else:
00091 update_dict = {header.user: int(header.request_id)}
00092 self._user_request_dict.update(update_dict)
00093 rospy.logdebug('add new user:%s' % header.user)
00094
00095 def _streaming_callback(self, request):
00096 """
00097 """
00098 with self._stream_client_lock:
00099 self._stream_client.add_streaming_packet(
00100 request.packet_type,
00101 request.packet_data
00102 )
00103
00104 def _streaming_config(self, request):
00105 """
00106 """
00107 client = None
00108 try:
00109 client = self._create_client(
00110 engine=request.engine,
00111 language=request.language,
00112 )
00113
00114 except Exception as err:
00115 rospy.logwarn(err)
00116 return False
00117
00118 with self._stream_client_lock:
00119 self._stream_client = client
00120
00121 return True
00122
00123 def _sync_callback(self, request):
00124 """ callback function for sr_req topic
00125 @param request: topic data
00126 @type request: str
00127 """
00128 rospy.loginfo(request)
00129 response = SpeechRecognitionResponse()
00130 response.header = request.header
00131
00132
00133 self._update_user_dictionary(request.header)
00134
00135
00136 try:
00137
00138 client = self._create_client(
00139 engine=request.header.engine,
00140 language=request.header.language
00141 )
00142
00143
00144 response.message = client.request(
00145 request.data,
00146 request.header.language
00147 )
00148
00149 client.join()
00150
00151 except ext.SpeechRecognitionException as err:
00152 rospy.logerr('[SpeechRecognitionException] ' + str(err))
00153 response.memo = str(err)
00154
00155 except ext.ParameterException as err:
00156 rospy.logerr('[ParameterException] ' + str(err))
00157 response.memo = str(err)
00158
00159 except ext.ServerException as err:
00160 rospy.logerr('[ServerException] ' + str(err))
00161 response.memo = str(err)
00162
00163
00164
00165 rospy.loginfo(response.header)
00166 self._publisher.publish(response)
00167
00168 def _create_client(self, engine, language):
00169 """ create client
00170 @param engine:
00171 @param language:
00172 """
00173 client = Factory.create(
00174 engine=engine,
00175 language=language,
00176 google_api_key=self._google_api_key,
00177 microsoft_api_key=self._microsoft_api_key
00178 )
00179 client.register_streaming_cb(
00180 self._publish_streaming_result
00181 )
00182 return client
00183
00184 def run(self):
00185 """ run rospeex sr node """
00186 rospy.init_node(self._MY_NODE_NAME)
00187
00188
00189 self._load_parameters()
00190
00191
00192 self._stream_client = self._create_client(
00193 engine=self._stream_engine,
00194 language=self._stream_language
00195 )
00196
00197 self._sr_config_service = rospy.Service(
00198 self._SPI_CONFIG_SERVICE_NAME,
00199 SpeechRecognitionConfig,
00200 self._streaming_config
00201 )
00202
00203
00204 rospy.Subscriber(
00205 self._REQUEST_TOPIC_NAME,
00206 SpeechRecognitionRequest,
00207 self._sync_callback
00208 )
00209
00210 rospy.Subscriber(
00211 self._STREAM_TOPIC_NAME,
00212 SignalProcessingStream,
00213 self._streaming_callback
00214 )
00215
00216
00217 self._publisher = rospy.Publisher(
00218 self._RESPONSE_TOPIC_NAME,
00219 SpeechRecognitionResponse,
00220 queue_size=10
00221 )
00222
00223 rospy.loginfo("start speech recognition node")
00224 rospy.spin()
00225
00226 def join(self, timeout=None):
00227 self._stream_client.join(timeout)
00228
00229
00230 def main():
00231 try:
00232 logging_util.setup_logging(use_ros_logging=True)
00233 node = SpeechRecognition()
00234 node.run()
00235
00236 except rospy.ROSInterruptException:
00237 pass
00238
00239 except Exception:
00240 rospy.logfatal(traceback.format_exc())
00241 return 2
00242
00243 finally:
00244 node.join()
00245
00246 return 1