From b8ff2b2947aaf69789f29913ae21933b6eeb87c9 Mon Sep 17 00:00:00 2001 From: Haiwei Luo <137087599+haiwei-luo@users.noreply.github.com> Date: Fri, 28 Jun 2024 13:28:02 +0100 Subject: [PATCH] Receptionist - bug fixes and increased robustness (#231) Co-authored-by: Zoe Co-authored-by: tiago --- .../assistants/receptionist/data/nlu.yml | 1 + .../scripts/test_microphones.py | 3 +- skills/src/lasr_skills/describe_people.py | 12 +- skills/src/lasr_skills/look_at_person.py | 28 ++- skills/src/lasr_skills/look_to_given_point.py | 2 +- tasks/receptionist/scripts/main.py | 9 +- .../src/receptionist/state_machine.py | 197 +++++++++++++++--- .../src/receptionist/states/get_attributes.py | 28 +++ .../src/receptionist/states/introduce.py | 57 ++--- 9 files changed, 254 insertions(+), 83 deletions(-) diff --git a/common/speech/lasr_rasa/assistants/receptionist/data/nlu.yml b/common/speech/lasr_rasa/assistants/receptionist/data/nlu.yml index 2b3eaeb44..cddd15417 100644 --- a/common/speech/lasr_rasa/assistants/receptionist/data/nlu.yml +++ b/common/speech/lasr_rasa/assistants/receptionist/data/nlu.yml @@ -25,6 +25,7 @@ nlu: - [Axel](name) - [Charlie](name) - [Jane](name) + - [Jayne](name) - [Jules](name) - [Morgan](name) - [Paris](name) diff --git a/common/speech/lasr_speech_recognition_whisper/scripts/test_microphones.py b/common/speech/lasr_speech_recognition_whisper/scripts/test_microphones.py index 39fd8fb96..418f9bb78 100644 --- a/common/speech/lasr_speech_recognition_whisper/scripts/test_microphones.py +++ b/common/speech/lasr_speech_recognition_whisper/scripts/test_microphones.py @@ -36,7 +36,8 @@ def main(args: dict) -> None: r = sr.Recognizer() with sr.Microphone(device_index=mic_index) as source: print("Say something!") - audio = r.listen(source) + audio = r.listen(source, timeout=5, phrase_time_limit=5) + print("Finished listening") with open(os.path.join(output_dir, "microphone.raw"), "wb") as f: f.write(audio.get_raw_data()) diff --git a/skills/src/lasr_skills/describe_people.py b/skills/src/lasr_skills/describe_people.py index bd55698bf..9368bc654 100755 --- a/skills/src/lasr_skills/describe_people.py +++ b/skills/src/lasr_skills/describe_people.py @@ -72,17 +72,7 @@ def __init__(self): rgb_topic=rgb_topic, use_mask=False, ), - transitions={"succeeded": "CONVERT_IMAGE", "failed": "SAY_CONTINUE"}, - ) - - smach.StateMachine.add( - "SAY_CONTINUE", - Say(text="I can't see anyone, I will continue"), - transitions={ - "succeeded": "failed", - "preempted": "failed", - "aborted": "failed", - }, + transitions={"succeeded": "CONVERT_IMAGE", "failed": "failed"}, ) smach.StateMachine.add( diff --git a/skills/src/lasr_skills/look_at_person.py b/skills/src/lasr_skills/look_at_person.py index fb9675c80..b31a3f8ea 100755 --- a/skills/src/lasr_skills/look_at_person.py +++ b/skills/src/lasr_skills/look_at_person.py @@ -20,6 +20,7 @@ import actionlib from control_msgs.msg import PointHeadAction, PointHeadGoal from geometry_msgs.msg import Point +from copy import copy PUBLIC_CONTAINER = False @@ -47,7 +48,7 @@ def __init__(self, debug=True, filter=False): "detections", "deepface_detection", ], - output_keys=["pointstamped"], + output_keys=["pointstamped", "bbox_eyes"], ) self.DEBUG = debug self.img_pub = rospy.Publisher("/debug/image", Image, queue_size=1) @@ -58,8 +59,10 @@ def __init__(self, debug=True, filter=False): self._filter = filter def execute(self, userdata): - rospy.sleep(1) - if len(userdata.bbox_eyes) < 1 and len(userdata.detections.detections) > 0: + rospy.sleep(0.1) + ######### BUG HERE REQUIRES RESOLVING ############### + if len(userdata.bbox_eyes) == 0 and len(userdata.detections.detections) > 0: + # userdata.pointstamped = PointStamped() return "succeeded" elif ( len(userdata.bbox_eyes) < 1 and len(userdata.detections.detections) < 1 @@ -88,7 +91,9 @@ def execute(self, userdata): else: return "failed" - for det in userdata.bbox_eyes: + bbox_eyes = copy(userdata.bbox_eyes) + + for det in bbox_eyes: left_eye = det["left_eye"] right_eye = det["right_eye"] eye_point = (left_eye[0] + right_eye[0]) / 2, ( @@ -268,6 +273,21 @@ def __init__(self, filter=False): transitions={"succeeded": "CHECK_EYES", "failed": "failed"}, remapping={"bbox_eyes": "bbox_eyes"}, ) + # smach.StateMachine.add( + # "CHECK_EYES", + # self.CheckEyes(self.DEBUG, filter=filter), + # transitions={ + # "succeeded": "LOOK_TO_POINT", + # "failed": "failed", + # "no_detection": "no_detection", + # }, + # remapping={ + # "pcl_msg": "pcl_msg", + # "bbox_eyes": "bbox_eyes", + # "pointstamped": "pointstamped", + # "deepface_detection": "deepface_detection", + # }, + # ) smach.StateMachine.add( "CHECK_EYES", self.CheckEyes(self.DEBUG, filter=filter), diff --git a/skills/src/lasr_skills/look_to_given_point.py b/skills/src/lasr_skills/look_to_given_point.py index 819906744..9c2347d5d 100755 --- a/skills/src/lasr_skills/look_to_given_point.py +++ b/skills/src/lasr_skills/look_to_given_point.py @@ -49,7 +49,7 @@ def execute(self, userdata): if finished_within_time: state = self.client.get_state() if state == GoalStatus.SUCCEEDED: - rospy.sleep(1) + rospy.sleep(0.1) return "succeeded" else: return "aborted" diff --git a/tasks/receptionist/scripts/main.py b/tasks/receptionist/scripts/main.py index 0bb75592c..fa5dc082f 100755 --- a/tasks/receptionist/scripts/main.py +++ b/tasks/receptionist/scripts/main.py @@ -38,18 +38,18 @@ "name": "charlie", "drink": "wine", "dataset": "receptionist", - "confidence": 0.5, + "detection": True, "attributes": { "has_hair": 0.5, "hair_shape": "straight hair", "hair_colour": "black hair", - "facial_hair": 0.5, + "facial_hair": 0, "earrings": 0, "necklace": 0, "necktie": 0, # "height": "unknown", "glasses": -0.5, - "hat": 0, + "hat": -0.5, "dress": 0, "top": 0.5, "outwear": 0, @@ -60,10 +60,7 @@ }, ) - sis = smach_ros.IntrospectionServer("smach_server", receptionist, "/SM_ROOT") - sis.start() outcome = receptionist.execute() - sis.stop() rospy.loginfo(f"Receptionist finished with outcome: {outcome}") rospy.spin() diff --git a/tasks/receptionist/src/receptionist/state_machine.py b/tasks/receptionist/src/receptionist/state_machine.py index b7c129390..409614c83 100755 --- a/tasks/receptionist/src/receptionist/state_machine.py +++ b/tasks/receptionist/src/receptionist/state_machine.py @@ -28,6 +28,7 @@ def __init__( seat_pose: Pose, seat_area: Polygon, host_data: dict, + face_detection_confidence: float = 0.2, ): smach.StateMachine.__init__(self, outcomes=["succeeded", "failed"]) @@ -37,9 +38,7 @@ def __init__( "guest1": {"name": ""}, "guest2": {"name": ""}, } - self.userdata.guest_name = "zoe" - self.userdata.dataset = "receptionist" - self.userdata.confidence = 0.15 + self.userdata.confidence = face_detection_confidence smach.StateMachine.add( "SAY_START", @@ -60,13 +59,13 @@ def __init__( GoToLocation(wait_pose), transitions={ "succeeded": "SAY_WAITING_GUEST_1", - "failed": "SAY_WAITING_GUEST_1", + "failed": "GO_TO_WAIT_LOCATION_GUEST_1", }, ) smach.StateMachine.add( "SAY_WAITING_GUEST_1", - Say(text="I am waiting for a guest."), + Say(text="I am waiting for a guest. Please open the door."), transitions={ "succeeded": "WAIT_FOR_PERSON_GUEST_1", "aborted": "WAIT_FOR_PERSON_GUEST_1", @@ -111,7 +110,7 @@ def __init__( smach.StateMachine.add( "REPEAT_GET_NAME_AND_DRINK_GUEST_1", AskAndListen( - "Sorry, I didn't get that. What is your name and favourite drink?" + "Sorry, I didn't get that, consider raising your voice. What is your name and favourite drink?" ), transitions={ "succeeded": "REPEAT_PARSE_NAME_AND_DRINK_GUEST_1", @@ -137,7 +136,9 @@ def __init__( smach.StateMachine.add( "REPEAT_GET_NAME_GUEST_1", - AskAndListen("Sorry, I didn't get your name. What is your name?"), + AskAndListen( + "Sorry, I didn't get your name. What is your name? Feel free to repeat your name several times." + ), transitions={ "succeeded": "REPEAT_PARSE_NAME_GUEST_1", "failed": "SAY_CONTINUE", @@ -161,7 +162,7 @@ def __init__( smach.StateMachine.add( "REPEAT_GET_DRINK_GUEST_1", AskAndListen( - "Sorry, I didn't get your favourite drink. What is your favourite drink?" + "Sorry, I didn't get your favourite drink. What is your favourite drink? Feel free to repeat your favourite drink several times." ), transitions={ "succeeded": "REPEAT_PARSE_DRINK_GUEST_1", @@ -213,7 +214,38 @@ def __init__( GetGuestAttributes("guest1"), transitions={ "succeeded": "SAY_LEARN_FACES", - "failed": "SAY_LEARN_FACES", + "failed": "SAY_GET_GUEST_ATTRIBUTE_1_FAILED", + }, + ) + + smach.StateMachine.add( + "SAY_GET_GUEST_ATTRIBUTE_1_FAILED", + Say( + text="Make sure you're looking into my eyes and facing me, I can't see you." + ), + transitions={ + "succeeded": "GET_GUEST_ATTRIBUTES_GUEST_1_AGAIN", + "aborted": "GET_GUEST_ATTRIBUTES_GUEST_1_AGAIN", + "preempted": "GET_GUEST_ATTRIBUTES_GUEST_1_AGAIN", + }, + ) + + smach.StateMachine.add( + "GET_GUEST_ATTRIBUTES_GUEST_1_AGAIN", + GetGuestAttributes("guest1"), + transitions={ + "succeeded": "SAY_LEARN_FACES", + "failed": "SAY_CONTINUE_GET_GUEST_ATTRIBUTES_GUEST_1", + }, + ) + + smach.StateMachine.add( + "SAY_CONTINUE_GET_GUEST_ATTRIBUTES_GUEST_1", + Say(text="I can't see anyone, I will continue"), + transitions={ + "succeeded": "SAY_LEARN_FACES", + "preempted": "SAY_LEARN_FACES", + "aborted": "SAY_LEARN_FACES", }, ) @@ -230,6 +262,27 @@ def __init__( smach.StateMachine.add( "LEARN_FACES", ReceptionistLearnFaces("guest1"), + transitions={ + "succeeded": "SAY_FOLLOW_GUEST_1", + "failed": "SAY_LEARN_FACES_FAILED", + }, + ) + + smach.StateMachine.add( + "SAY_LEARN_FACES_FAILED", + Say( + text="Make sure you're looking into my eyes and staying still, I'll try and learn your face again" + ), + transitions={ + "succeeded": "LEARN_FACES_RECOVERY", + "preempted": "LEARN_FACES_RECOVERY", + "aborted": "LEARN_FACES_RECOVERY", + }, + ) + + smach.StateMachine.add( + "LEARN_FACES_RECOVERY", + ReceptionistLearnFaces("guest1"), transitions={ "succeeded": "SAY_FOLLOW_GUEST_1", "failed": "SAY_FOLLOW_GUEST_1", @@ -251,13 +304,15 @@ def __init__( GoToLocation(seat_pose), transitions={ "succeeded": "SAY_WAIT_GUEST_1", - "failed": "SAY_WAIT_GUEST_1", + "failed": "GO_TO_SEAT_LOCATION_GUEST_1", }, ) smach.StateMachine.add( "SAY_WAIT_GUEST_1", - Say(text="Please wait here on my left"), + Say( + text="Please wait here on my left. Can the seated host look into my eyes please." + ), transitions={ "succeeded": "FIND_AND_LOOK_AT", "preempted": "failed", @@ -338,7 +393,17 @@ def __init__( SeatGuest(seat_area), transitions={ "succeeded": "SAY_RETURN_WAITING_AREA", - "failed": "SAY_RETURN_WAITING_AREA", + "failed": "SAY_SEAT_GUEST_1_FAILED", + }, + ) + + smach.StateMachine.add( + "SAY_SEAT_GUEST_1_FAILED", + Say(text="I can't see a free seat, please sit down somewhere."), + transitions={ + "succeeded": "SAY_RETURN_WAITING_AREA", + "aborted": "SAY_RETURN_WAITING_AREA", + "preempted": "SAY_RETURN_WAITING_AREA", }, ) @@ -361,13 +426,13 @@ def __init__( GoToLocation(wait_pose), transitions={ "succeeded": "SAY_WAITING_GUEST_2", - "failed": "SAY_WAITING_GUEST_2", + "failed": "GO_TO_WAIT_LOCATION_GUEST_2", }, ) smach.StateMachine.add( "SAY_WAITING_GUEST_2", - Say(text="I am waiting for a guest."), + Say(text="I am waiting for a guest. Please open the door."), transitions={ "succeeded": "WAIT_FOR_PERSON_GUEST_2", "aborted": "WAIT_FOR_PERSON_GUEST_2", @@ -412,7 +477,7 @@ def __init__( smach.StateMachine.add( "REPEAT_GET_NAME_AND_DRINK_GUEST_2", AskAndListen( - "Sorry, I didn't get that. What is your name and favourite drink?" + "Sorry, I didn't get that, consider raising your voice. What is your name and favourite drink?" ), transitions={ "succeeded": "REPEAT_PARSE_NAME_AND_DRINK_GUEST_2", @@ -438,7 +503,9 @@ def __init__( smach.StateMachine.add( "REPEAT_GET_NAME_GUEST_2", - AskAndListen("Sorry, I didn't get your name. What is your name?"), + AskAndListen( + "Sorry, I didn't get your name. What is your name? Feel free to repeat your name several times." + ), transitions={ "succeeded": "REPEAT_PARSE_NAME_GUEST_2", "failed": "SAY_CONTINUE_GUEST_2", @@ -462,7 +529,7 @@ def __init__( smach.StateMachine.add( "REPEAT_GET_DRINK_GUEST_2", AskAndListen( - "Sorry, I didn't get your favourite drink. What is your favourite drink?" + "Sorry, I didn't get your favourite drink. What is your favourite drink? Feel free to repeat your favourite drink several times." ), transitions={ "succeeded": "REPEAT_PARSE_DRINK_GUEST_2", @@ -506,30 +573,61 @@ def __init__( "GET_GUEST_ATTRIBUTES_GUEST_2", GetGuestAttributes("guest2"), transitions={ - "succeeded": "SAY_LEARN_FACES_GUEST_2", - "failed": "SAY_LEARN_FACES_GUEST_2", + "succeeded": "SAY_FOLLOW_GUEST_2", + "failed": "SAY_GET_GUEST_ATTRIBUTE_2_FAILED", + }, + ) + + smach.StateMachine.add( + "SAY_GET_GUEST_ATTRIBUTE_2_FAILED", + Say( + text="Make sure you're looking into my eyes and facing me, I can't see you." + ), + transitions={ + "succeeded": "GET_GUEST_ATTRIBUTES_GUEST_2_AGAIN", + "aborted": "GET_GUEST_ATTRIBUTES_GUEST_2_AGAIN", + "preempted": "GET_GUEST_ATTRIBUTES_GUEST_2_AGAIN", }, ) smach.StateMachine.add( - "SAY_LEARN_FACES_GUEST_2", - Say(text="Continue looking into my eyes, I'm about to learn your face"), + "GET_GUEST_ATTRIBUTES_GUEST_2_AGAIN", + GetGuestAttributes("guest1"), transitions={ - "succeeded": "LEARN_FACES_GUEST_2", - "preempted": "LEARN_FACES_GUEST_2", - "aborted": "LEARN_FACES_GUEST_2", + "succeeded": "SAY_FOLLOW_GUEST_2", + "failed": "SAY_CONTINUE_GET_GUEST_ATTRIBUTES_GUEST_2", }, ) smach.StateMachine.add( - "LEARN_FACES_GUEST_2", - ReceptionistLearnFaces("guest2"), + "SAY_CONTINUE_GET_GUEST_ATTRIBUTES_GUEST_2", + Say(text="I can't see anyone, I will continue"), transitions={ "succeeded": "SAY_FOLLOW_GUEST_2", - "failed": "SAY_FOLLOW_GUEST_2", + "preempted": "SAY_FOLLOW_GUEST_2", + "aborted": "SAY_FOLLOW_GUEST_2", }, ) + # smach.StateMachine.add( + # "SAY_LEARN_FACES_GUEST_2", + # Say(text="Continue looking into my eyes, I'm about to learn your face"), + # transitions={ + # "succeeded": "LEARN_FACES_GUEST_2", + # "preempted": "LEARN_FACES_GUEST_2", + # "aborted": "LEARN_FACES_GUEST_2", + # }, + # ) + + # smach.StateMachine.add( + # "LEARN_FACES_GUEST_2", + # ReceptionistLearnFaces("guest2"), + # transitions={ + # "succeeded": "SAY_FOLLOW_GUEST_2", + # "failed": "SAY_FOLLOW_GUEST_2", + # }, + # ) + smach.StateMachine.add( "SAY_FOLLOW_GUEST_2", Say(text="Please follow me, I will guide you to the other guests"), @@ -545,13 +643,15 @@ def __init__( GoToLocation(seat_pose), transitions={ "succeeded": "SAY_WAIT_GUEST_2", - "failed": "SAY_WAIT_GUEST_2", + "failed": "GO_TO_SEAT_LOCATION_GUEST_2", }, ) smach.StateMachine.add( "SAY_WAIT_GUEST_2", - Say(text="Please wait here on my left"), + Say( + text="Please wait here on my left. Can the seated host look into my eyes please." + ), transitions={ "succeeded": "FIND_AND_LOOK_AT_HOST_2", "preempted": "failed", @@ -606,9 +706,28 @@ def __init__( LookToGivenPoint( [-1.5, 0.0], ), + transitions={ + "succeeded": "INTRODUCE_GUEST_HOST_TO_GUEST_2", + "timed_out": "INTRODUCE_GUEST_HOST_TO_GUEST_2", + "aborted": "INTRODUCE_GUEST_HOST_TO_GUEST_2", + }, + ) + + smach.StateMachine.add( + "INTRODUCE_GUEST_HOST_TO_GUEST_2", + Introduce(guest_to_introduce="host", guest_to_introduce_to="guest2"), + transitions={ + "succeeded": "SAY_WAIT_GUEST_2_SEATED_GUEST_1", + "failed": "SAY_WAIT_GUEST_2_SEATED_GUEST_1", + }, + ) + + smach.StateMachine.add( + "SAY_WAIT_GUEST_2_SEATED_GUEST_1", + Say(text="Can the seated guest look into my eyes please."), transitions={ "succeeded": "FIND_AND_LOOK_AT_GUEST_1", - "timed_out": "FIND_AND_LOOK_AT_GUEST_1", + "preempted": "FIND_AND_LOOK_AT_GUEST_1", "aborted": "FIND_AND_LOOK_AT_GUEST_1", }, ) @@ -629,6 +748,9 @@ def __init__( }, ) + # Check if host is sat where they are sat + # Look at the host + smach.StateMachine.add( "LOOK_AT_WAITING_GUEST_2_3", LookToGivenPoint( @@ -662,6 +784,7 @@ def __init__( }, ) + # Look at guest 1 smach.StateMachine.add( "INTRODUCE_GUEST_1_TO_GUEST_2", Introduce(guest_to_introduce="guest1", guest_to_introduce_to="guest2"), @@ -676,7 +799,17 @@ def __init__( SeatGuest(seat_area), transitions={ "succeeded": "SAY_GOODBYE", - "failed": "SAY_GOODBYE", + "failed": "SAY_SEAT_GUEST_2_FAILED", + }, + ) + + smach.StateMachine.add( + "SAY_SEAT_GUEST_2_FAILED", + Say(text="I can't see a free seat, please sit down somewhere."), + transitions={ + "succeeded": "SAY_GOODBYE", + "aborted": "SAY_GOODBYE", + "preempted": "SAY_GOODBYE", }, ) @@ -700,7 +833,7 @@ def __init__( GoToLocation(wait_pose), transitions={ "succeeded": "SAY_FINISHED", - "failed": "SAY_FINISHED", + "failed": "GO_TO_FINISH_LOCATION", }, ) smach.StateMachine.add( diff --git a/tasks/receptionist/src/receptionist/states/get_attributes.py b/tasks/receptionist/src/receptionist/states/get_attributes.py index 6fcca9bc1..106230313 100644 --- a/tasks/receptionist/src/receptionist/states/get_attributes.py +++ b/tasks/receptionist/src/receptionist/states/get_attributes.py @@ -5,6 +5,25 @@ class GetGuestAttributes(smach.StateMachine): + class InitialiseDetectionFlag(smach.State): + def __init__(self, guest_id: str): + smach.State.__init__( + self, + outcomes=["succeeded", "failed"], + input_keys=["guest_data"], + output_keys=["guest_data"], + ) + + self._guest_id: str = guest_id + + def execute(self, userdata: UserData) -> str: + try: + userdata.guest_data[self._guest_id]["detection"] = False + return "succeeded" + except Exception as e: + print(e) + return "failed" + class HandleGuestAttributes(smach.State): def __init__(self, guest_id: str): smach.State.__init__( @@ -22,6 +41,7 @@ def execute(self, userdata: UserData) -> str: userdata.guest_data[self._guest_id]["attributes"] = json.loads( userdata.people[0]["features"] ) + userdata.guest_data[self._guest_id]["detection"] = True return "succeeded" def __init__( @@ -37,6 +57,14 @@ def __init__( self._guest_id: str = guest_id with self: + smach.StateMachine.add( + "INITIALISE_DETECTION_FLAG", + self.InitialiseDetectionFlag(self._guest_id), + transitions={ + "succeeded": "GET_GUEST_ATTRIBUTES", + "failed": "GET_GUEST_ATTRIBUTES", + }, + ) smach.StateMachine.add( "GET_GUEST_ATTRIBUTES", DescribePeople(), diff --git a/tasks/receptionist/src/receptionist/states/introduce.py b/tasks/receptionist/src/receptionist/states/introduce.py index cf71d1aed..40c0c8754 100644 --- a/tasks/receptionist/src/receptionist/states/introduce.py +++ b/tasks/receptionist/src/receptionist/states/introduce.py @@ -11,31 +11,6 @@ from typing import Dict, List, Any, Optional -def find_most_confident_clothes( - relevant_guest_data: Dict[str, Any], clothes: List[List[Any]] -) -> List[Any]: - """Find the clothes it's most confident of, after determining the clothes type - through confidence values. - - Args: - relevant_guest_data (Dict[str, Any]): guest data dictionary. - clothes List[List[Any]]: List of the clothes type and their confidence - - Returns: - List: Maximum confidence and the relevant clothes - """ - max_clothes_type, max_confidence = max(clothes, key=lambda c: c[1]) - - if max_clothes_type == "dress": - max_clothes = relevant_guest_data["attributes"]["max_dress"] - elif max_clothes_type == "top": - max_clothes = relevant_guest_data["attributes"]["max_top"] - else: - max_clothes = relevant_guest_data["attributes"]["max_outwear"] - - return [max_confidence, max_clothes] - - def stringify_guest_data(guest_data: Dict[str, Any], guest_id: str) -> str: """Converts the guest data for a specified guest into a string that can be used for the robot to introduce the guest to the other guests/host. @@ -75,10 +50,11 @@ def stringify_guest_data(guest_data: Dict[str, Any], guest_id: str) -> str: guest_str += f"{relevant_guest_data['name']}, their favourite drink is {relevant_guest_data['drink']}. " - clothes = ["dress", "top", "outwear"] + if relevant_guest_data["detection"] == False: + guest_str += "No attributes were detected for them." + return guest_str filtered_attributes = {} - filtered_attributes["hair"] = { "confidence": relevant_guest_data["attributes"]["has_hair"], "hair_shape": relevant_guest_data["attributes"]["hair_shape"], @@ -163,8 +139,33 @@ def stringify_guest_data(guest_data: Dict[str, Any], guest_id: str) -> str: return guest_str +def find_most_confident_clothes( + relevant_guest_data: Dict[str, Any], clothes: List[List[Any]] +) -> List[Any]: + """Find the clothes it's most confident of, after determining the clothes type + through confidence values. + + Args: + relevant_guest_data (Dict[str, Any]): guest data dictionary. + clothes List[List[Any]]: List of the clothes type and their confidence + + Returns: + List: Maximum confidence and the relevant clothes + """ + max_clothes_type, max_confidence = max(clothes, key=lambda c: c[1]) + + if max_clothes_type == "dress": + max_clothes = relevant_guest_data["attributes"]["max_dress"] + elif max_clothes_type == "top": + max_clothes = relevant_guest_data["attributes"]["max_top"] + else: + max_clothes = relevant_guest_data["attributes"]["max_outwear"] + + return [max_confidence, max_clothes] + + def isSingular(attribute: str): - """Checks is a word is singular or plural by checking the last letter + """Checks if a word is singular or plural by checking the last letter Args: attribute (str): The attribute to check for plurality