diff --git a/common/speech/lasr_speech_recognition_whisper/nodes/transcribe_microphone_server b/common/speech/lasr_speech_recognition_whisper/nodes/transcribe_microphone_server index f0373e0b1..6f6c87552 100644 --- a/common/speech/lasr_speech_recognition_whisper/nodes/transcribe_microphone_server +++ b/common/speech/lasr_speech_recognition_whisper/nodes/transcribe_microphone_server @@ -91,7 +91,7 @@ class TranscribeSpeechAction(object): self._model_params.warmup, ) # Configure the speech recogniser object and adjust for ambient noise - self.recogniser = self._configure_recogniser(ambient_adj=False) + self.recogniser = self._configure_recogniser(ambient_adj=True) # Setup the action server and register execution callback self._action_server = actionlib.SimpleActionServer( self._action_name, diff --git a/tasks/qualification/launch/better_qualification.launch b/tasks/qualification/launch/better_qualification.launch index a3a6e2093..bbbded770 100644 --- a/tasks/qualification/launch/better_qualification.launch +++ b/tasks/qualification/launch/better_qualification.launch @@ -3,7 +3,7 @@ - + diff --git a/tasks/qualification/nodes/actions/guide b/tasks/qualification/nodes/actions/guide index 44464c338..df3305b76 100644 --- a/tasks/qualification/nodes/actions/guide +++ b/tasks/qualification/nodes/actions/guide @@ -21,8 +21,8 @@ class Guide: ), "edges": { "corridor": Pose( - position=Point(4.68, 6.87, 0.0), - orientation=Quaternion(0.0, 0.0, 0.59, 0.80), + position=Point(4.27, 5.64, 0.0), + orientation=Quaternion(0.0, 0.0, -0.87, 0.50), ) }, }, @@ -33,8 +33,8 @@ class Guide: ), "edges": { "lab": Pose( - position=Point(4.09, 8.21, 0.0), - orientation=Quaternion(0.0, 0.0, 0.91, 0.40), + position=Point(4.05, 9.28, 0.0), + orientation=Quaternion(0.0, 0.0, -0.74, 0.68), ), "kitchen": None, }, @@ -120,7 +120,6 @@ class Guide: f"{goal.guidee}, could you please get the door for me?" ) self.tts.send_goal_and_wait(tts_goal) - # TODO: check if the door is open using CLIP door_closed = self.check_for_door() counter = 1 while door_closed: diff --git a/tasks/qualification/nodes/better_qualification b/tasks/qualification/nodes/better_qualification index 9327c638e..61c2bd1c8 100644 --- a/tasks/qualification/nodes/better_qualification +++ b/tasks/qualification/nodes/better_qualification @@ -117,6 +117,10 @@ point.positions = [0.15] point.time_from_start = rospy.Duration(1) torso_lower_goal.trajectory.points.append(point) +tts_goal = TtsGoal() +tts_goal.rawtext.lang_id = "en_GB" +tts_goal.rawtext.text = "Begin" +tts.send_goal_and_wait(tts_goal) # Wait to be greeted wait_greet.send_goal_and_wait(WaitGreetGoal()) @@ -151,3 +155,4 @@ while not rospy.is_shutdown(): # Execute the command command = command_result.command exec_command(command) + rospy.sleep(3.0)