Skip to content

Commit

Permalink
Receptionist - bug fixes and increased robustness (#231)
Browse files Browse the repository at this point in the history
Co-authored-by: Zoe <ezoe013@gmail.com>
Co-authored-by: tiago <example@example.com>
  • Loading branch information
3 people authored Jun 28, 2024
1 parent 77b66a8 commit b8ff2b2
Show file tree
Hide file tree
Showing 9 changed files with 254 additions and 83 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ nlu:
- [Axel](name)
- [Charlie](name)
- [Jane](name)
- [Jayne](name)
- [Jules](name)
- [Morgan](name)
- [Paris](name)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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())
Expand Down
12 changes: 1 addition & 11 deletions skills/src/lasr_skills/describe_people.py
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down
28 changes: 24 additions & 4 deletions skills/src/lasr_skills/look_at_person.py
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down Expand Up @@ -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)
Expand All @@ -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
Expand Down Expand Up @@ -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, (
Expand Down Expand Up @@ -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),
Expand Down
2 changes: 1 addition & 1 deletion skills/src/lasr_skills/look_to_given_point.py
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
9 changes: 3 additions & 6 deletions tasks/receptionist/scripts/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand All @@ -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()
Loading

0 comments on commit b8ff2b2

Please sign in to comment.