def _determine_answer(self, description, grammar, target, is_preempt_requested): grammar_parser = CFGParser.fromstring(grammar) grammar_parser.verify(target) self.start_listen_client.wait_for_service() self.start_listen_client.call() timeout = 10 score = 0.0 while score < 0.8: # Now wait for result try: result = rospy.wait_for_message("/hsrb/voice/text", RecognitionResult, timeout) except rospy.ROSException: self.stop_listen_client.call() return None score = result.scores[0] self.stop_listen_client.call() sentence = result.sentences[0] rospy.loginfo("Julius Client received sentence %s", sentence) if result is None: return None semantics = grammar_parser.parse(target, sentence) return HMIResult(sentence, semantics)
def _handle_failed_hmi(userdata=None): """ Handle failed HMI queries so we can try up to x times """ self._location_hmi_attempt += 1 # Increment if self._location_hmi_attempt == self._max_hmi_attempts: rospy.logwarn( "HMI failed for the {} time, returning 'failed'". format(self._max_hmi_attempts)) if not BACKUP_SCENARIOS: rospy.logwarn( "No fallback scenario's available anymore") return "failed" backup = BACKUP_SCENARIOS.pop(0) robot.speech.speak("I am sorry but I did not hear you", mood="sad", block=False) robot.speech.speak(backup.sentence, block=False) self.answer_des.writeable.write( HMIResult("", backup.entity_id)) return "fallback" rospy.loginfo( "HMI failed for the {} time out of {}, retrying".format( self._location_hmi_attempt, self._max_hmi_attempts)) return "retry"
def _determine_answer(self, description, grammar, target, is_preempt_requested): c = DragonflyClient(*self._address) result = c.recognize(grammar, target, is_preempt_requested) if result is None: return None semantics, sentence = result return HMIResult(sentence, semantics)
def _determine_answer(self, description, grammar, target, is_preempt_requested): rospy.loginfo( "_determine_answer: Need to determine answer to '{}'".format( description)) if not description: #Cannot handle empty questions err = "Cannot answer empty question. grammar='{g}...', target='{t}'".format( g=grammar[:10], t=target) # raise Exception(err) # TODO: Client cannot yet handle this rospy.logerr(err) return HMIResult(err, {}) self._answer_needed = True # Pose the question to the user via the chat self._bot.send_message(chat_id=self._chat_id, text=description) rospy.loginfo("Passed question to user") # self._wait_for_answer.wait() while not self._answer: rospy.logdebug("Wait for answer...") time.sleep(0.5) rospy.loginfo("Received answer: '%s'", self._answer) sanitized = self.sanitize_text(self._answer.replace("/answer ", "")) semantics = parse_sentence(sanitized, grammar, target) rospy.loginfo("Parsed semantics: %s", semantics) result = HMIResult(sanitized, semantics) self._answer = None self._answer_needed = False # self._wait_for_answer.clear() return result
def _determine_answer(self, description, grammar, target, is_preempt_requested): if is_preempt_requested and self._target: rospy.logwarn("Preempt requested while a query was being answered") self._answer_ready.set() else: rospy.logwarn( "Preempt requested while NO query was being answered") rospy.loginfo('Sending to telegram') self._intermediate_answer = [] self._target = target self._grammar_parser = CFGParser.fromstring(grammar) self._grammar_parser.verify() self._options_pub.publish( Options(question=description, options=sorted( set( self._grammar_parser.next_word( self._target, self._intermediate_answer))))) start = rospy.Time.now() while not rospy.is_shutdown() and \ rospy.Time.now() < start + rospy.Duration(self._timeout) and \ not self._answer_ready.isSet(): self._answer_ready.wait(1) if self._answer_ready.is_set(): rospy.loginfo("Answer is ready") self._answer_ready.clear() try: sentence = self.intermediate_sentence rospy.loginfo("Gathered sentence: %s", sentence) if sentence: semantics = parse_sentence(sentence, grammar, target) rospy.loginfo("Parsed semantics: %s", semantics) self._message_pub.publish( "Completed sentence: '{}'. Thnx!".format(sentence)) self._intermediate_answer = [] self._target = '' return HMIResult(sentence, semantics) except Exception: raise else: self._message_pub.publish("Sorry, that took too long") rospy.loginfo("Telegram took to look to complete the query")
def _determine_answer(self, description, grammar, target, is_preempt_requested): # type: (str, str, str, Func) -> None """ Method override to start speech recognition upon receiving a query from the HMI server :param description: (str) description of the HMI request :param grammar: (str) grammar that should be used :param target: (str) target that should be obtained from the grammar :param is_preempt_requested: (callable) checks whether a preempt is requested by the hmi client """ rospy.loginfo("Need an answer from ASR for '{}'".format(description)) self._completed_string = None self._speech_stopped.clear() if self._voice_timer: self._voice_timer.shutdown() self._voice_timer = None verify_grammar(grammar) self._pipeline.start() while not rospy.is_shutdown() and \ not is_preempt_requested() and \ not self._completed_string and \ not self._speech_stopped.is_set(): rospy.logdebug("Sleep") rospy.sleep(.1) if rospy.is_shutdown() or is_preempt_requested(): rospy.loginfo("Stop") self._pipeline.stop() return None rospy.loginfo("Received string: '%s'", self._completed_string) semantics = parse_sentence(self._completed_string, grammar, target) rospy.loginfo("Parsed semantics: %s", semantics) result = HMIResult(self._completed_string, semantics) self._pipeline.stop() self._completed_string = None return result
from robot_smach_states.util.designators.string_manipulation import FieldOfHMIResult from robot_smach_states.util.designators.core import Designator if __name__ == "__main__": parser = argparse.ArgumentParser( description="Test the string manipulation") args = parser.parse_args() rospy.init_node("Set_gripper_state") # Test 1 from docstrings query_result = HMIResult( sentence='ignored', semantics={u'widget': { u'gadget': { u'bla': u'foo', u'bar': u'buzz' } }}) query_des = Designator(query_result, name="d1") field_des = FieldOfHMIResult(query_des, semantics_path=['widget', 'gadget', 'bar']) rospy.loginfo(field_des.resolve()) # Test 2 from docstrings query_result2 = HMIResult(sentence='ignored', semantics=u'dinges') query_des2 = Designator(query_result2, name="d2") field_des2 = FieldOfHMIResult(query_des2, semantics_path=[]) rospy.loginfo(field_des2.resolve())
def mock_query(description, grammar, target, timeout): sentence = random_sentence(grammar, target) semantics = parse_sentence(sentence, grammar, target) return HMIResult(sentence=sentence, semantics=semantics)