4 import dialogflow_v2beta1
     5 from dialogflow_v2beta1.types 
import Context, EventInput, InputAudioConfig, \
     6     OutputAudioConfig, QueryInput, QueryParameters, \
     7     StreamingDetectIntentRequest, TextInput
     8 from dialogflow_v2beta1.gapic.enums 
import AudioEncoding, OutputAudioEncoding
     9 import google.api_core.exceptions
    11 from AudioServerStream 
import AudioServerStream
    12 from MicrophoneStream 
import MicrophoneStream
    19 from uuid 
import uuid4
    20 from yaml 
import load, YAMLError
    24 from std_msgs.msg 
import String
    32     def __init__(self, language_code='en-US', last_contexts=None):
    33         """Initialize all params and load data"""    34         """ Constants and params """    40         self.
PLAY_AUDIO = rospy.get_param(
'/dialogflow_client/play_audio', 
True)
    41         self.
DEBUG = rospy.get_param(
'/dialogflow_client/debug', 
False)
    46         """ Dialogflow setup """    49         file_dir = rp.get_path(
'dialogflow_ros') + 
'/config/context.yaml'    50         with open(file_dir, 
'r') as f:    54                 rospy.logwarn(
"DF_CLIENT: Unable to open phrase hints yaml file!")
    58         project_id = rospy.get_param(
'/dialogflow_client/project_id', 
'my-project-id')
    59         session_id = str(uuid4())  
    63         audio_encoding = AudioEncoding.AUDIO_ENCODING_LINEAR_16
    67                                               sample_rate_hertz=self.
RATE,
    69                                               model=
'command_and_search')
    71                 audio_encoding=OutputAudioEncoding.OUTPUT_AUDIO_ENCODING_LINEAR_16
    75         self.
_session = self._session_cli.session_path(project_id, session_id)
    76         rospy.logdebug(
"DF_CLIENT: Session Path: {}".format(self.
_session))
    79         results_topic = rospy.get_param(
'/dialogflow_client/results_topic',
    80                                         '/dialogflow_client/results')
    81         requests_topic = rospy.get_param(
'/dialogflow_client/requests_topic',
    82                                          '/dialogflow_client/requests')
    83         text_req_topic = requests_topic + 
'/string_msg'    84         text_event_topic = requests_topic + 
'/string_event'    85         msg_req_topic = requests_topic + 
'/df_msg'    86         event_req_topic = requests_topic + 
'/df_event'    87         self.
_results_pub = rospy.Publisher(results_topic, DialogflowResult,
    91         rospy.Subscriber(msg_req_topic, DialogflowRequest, self.
_msg_request_cb)
    97         self.
_server_name = rospy.get_param(
'/dialogflow_client/server_name',
    99         self.
_port = rospy.get_param(
'/dialogflow_client/port', 4444)
   104         rospy.logdebug(
"DF_CLIENT: Last Contexts: {}".format(self.
last_contexts))
   105         rospy.loginfo(
"DF_CLIENT: Ready!")
   112         """ROS Callback that sends text received from a topic to Dialogflow,   113         :param msg: A String message.   116         rospy.logdebug(
"DF_CLIENT: Request received")
   117         new_msg = DialogflowRequest(query_text=msg.data)
   121         """ROS Callback that sends text received from a topic to Dialogflow,   122         :param msg: A DialogflowRequest message.   123         :type msg: DialogflowRequest   126         rospy.logdebug(
"DF_CLIENT: Request received:\n{}".format(df_msg))
   130         :param msg: DialogflowEvent Message   131         :type msg: DialogflowEvent"""   132         new_event = utils.converters.events_msg_to_struct(msg)
   136         new_event = EventInput(name=msg.data, language_code=self.
_language_code)
   147         assert isinstance(language_code, str), 
"Language code must be a string!"   155         rospy.logwarn(
"\nDF_CLIENT: SIGINT caught!")
   163         """Creates a PyAudio output stream."""   164         rospy.logdebug(
"DF_CLIENT: Creating audio output...")
   171         """Simple function to play a the output Dialogflow response.   172         :param data: Audio in bytes.   174         self.stream_out.start_stream()
   175         self.stream_out.write(data)
   177         self.stream_out.stop_stream()
   184         """Generator function that continuously yields audio chunks from the   185         buffer. Used to stream data to the Google Speech API Asynchronously.   186         :return A streaming request with the audio data.   187         First request carries config data per Dialogflow docs.   188         :rtype: Iterator[:class:`StreamingDetectIntentRequest`]   192         contexts = utils.converters.contexts_msg_to_struct(self.
last_contexts)
   193         params = QueryParameters(contexts=contexts)
   194         req = StreamingDetectIntentRequest(
   196                 query_input=query_input,
   198                 single_utterance=
True,
   204             with AudioServerStream() 
as stream:
   205                 audio_generator = stream.generator()
   206                 for content 
in audio_generator:
   207                     yield StreamingDetectIntentRequest(input_audio=content)
   209             with MicrophoneStream() 
as stream:
   210                 audio_generator = stream.generator()
   211                 for content 
in audio_generator:
   212                     yield StreamingDetectIntentRequest(input_audio=content)
   219         """Use the Dialogflow API to detect a user's intent. Goto the Dialogflow   220         console to define intents and params.   221         :param msg: DialogflowRequest msg   222         :return query_result: Dialogflow's query_result with action parameters   223         :rtype: DialogflowResult   226         text_input = TextInput(text=msg.query_text, language_code=self.
_language_code)
   227         query_input = QueryInput(text=text_input)
   229         user_contexts = utils.converters.contexts_msg_to_struct(msg.contexts)
   232         params = QueryParameters(contexts=contexts)
   234             response = self._session_cli.detect_intent(
   236                     query_input=query_input,
   240         except google.api_core.exceptions.ServiceUnavailable:
   241             rospy.logwarn(
"DF_CLIENT: Deadline exceeded exception caught. The response "   242                           "took too long or you aren't connected to the internet!")
   245             self.
last_contexts = utils.converters.contexts_struct_to_msg(
   246                     response.query_result.output_contexts
   248             df_msg = utils.converters.result_struct_to_msg(
   249                     response.query_result)
   250             rospy.loginfo(utils.output.print_result(response.query_result))
   254             self._results_pub.publish(df_msg)
   258         """Gets data from an audio generator (mic) and streams it to Dialogflow.   259         We use a stream for VAD and single utterance detection."""   263         responses = self._session_cli.streaming_detect_intent(requests)
   266             for response 
in responses:
   267                 resp_list.append(response)
   269                         'DF_CLIENT: Intermediate transcript: "{}".'.format(
   270                                 response.recognition_result.transcript))
   271         except google.api_core.exceptions.Cancelled 
as c:
   272             rospy.logwarn(
"DF_CLIENT: Caught a Google API Client cancelled "   273                           "exception. Check request format!:\n{}".format(c))
   274         except google.api_core.exceptions.Unknown 
as u:
   275             rospy.logwarn(
"DF_CLIENT: Unknown Exception Caught:\n{}".format(u))
   276         except google.api_core.exceptions.ServiceUnavailable:
   277             rospy.logwarn(
"DF_CLIENT: Deadline exceeded exception caught. The response "   278                           "took too long or you aren't connected to the internet!")
   281                 rospy.logwarn(
"DF_CLIENT: No response received!")
   287             final_result = resp_list[-2].query_result
   288             final_audio = resp_list[-1]
   289             self.
last_contexts = utils.converters.contexts_struct_to_msg(
   290                     final_result.output_contexts
   292             df_msg = utils.converters.result_struct_to_msg(final_result)
   293             rospy.loginfo(utils.output.print_result(final_result))
   298             self._results_pub.publish(df_msg)
   299             if return_result: 
return df_msg, final_result
   303         """Send an event message to Dialogflow   304         :param event: The ROS event message   305         :type event: DialogflowEvent   306         :return: The result from dialogflow as a ROS msg   307         :rtype: DialogflowResult   310         if type(event) 
is DialogflowEvent:
   311             event_input = utils.converters.events_msg_to_struct(event)
   315         query_input = QueryInput(event=event_input)
   316         params = utils.converters.create_query_parameters(
   319         response = self._session_cli.detect_intent(
   321                 query_input=query_input,
   325         df_msg = utils.converters.result_struct_to_msg(response.query_result)
   331         """Start the dialogflow client"""   332         rospy.loginfo(
"DF_CLIENT: Spinning...")
   336         """Close as cleanly as possible"""   337         rospy.loginfo(
"DF_CLIENT: Shutting down")
   338         self.audio.terminate()
   342 if __name__ == 
'__main__':
   343     rospy.init_node(
'dialogflow_client')
 
def _play_stream(self, data)
def _event_request_cb(self, msg)
def event_intent(self, event)
def set_language_code(self, language_code)
def _msg_request_cb(self, msg)
def _text_request_cb(self, msg)
def __init__(self, language_code='en-US', last_contexts=None)
def _text_event_cb(self, msg)
def detect_intent_text(self, msg)
def _create_audio_output(self)
def get_language_code(self)
def detect_intent_stream(self, return_result=False)
def _signal_handler(self, signal, frame)