Skip to content

Commit

Permalink
feat: get name and drink, and stub for attributes.
Browse files Browse the repository at this point in the history
  • Loading branch information
jws-1 committed Apr 11, 2024
1 parent d6e9929 commit ca58f85
Showing 1 changed file with 34 additions and 1 deletion.
35 changes: 34 additions & 1 deletion tasks/receptionist/src/receptionist/receptionist.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,9 @@
from geometry_msgs.msg import Pose, Point, Quaternion
from shapely.geometry import Polygon

from lasr_skills import GoToLocation, WaitForPersonInArea, Say
from receptionist.states import ParseNameAndDrink, GetGuestAttributes

from lasr_skills import GoToLocation, WaitForPersonInArea, Say, AskAndListen


class Receptionist(smach.StateMachine):
Expand All @@ -16,6 +18,9 @@ def __init__(self, wait_pose: Pose, wait_area: Polygon):

with self:

self.userdata.guest_id = "guest1"
self.userdata.guest_data = {}

smach.StateMachine.add(
"GO_TO_WAIT_LOCATION",
GoToLocation(wait_pose),
Expand Down Expand Up @@ -44,6 +49,34 @@ def __init__(self, wait_pose: Pose, wait_area: Polygon):
},
)

smach.StateMachine.add(
"GET_NAME_AND_DRINK",
AskAndListen("What is your name and favourite drink?"),
transitions={
"succeeded": "PARSE_NAME_AND_DRINK",
"failed": "failed",
},
)

smach.StateMachine.add(
"PARSE_NAME_AND_DRINK",
ParseNameAndDrink(),
transitions={
"succeeded": "GET_GUEST_ATTRIBUTES",
"failed": "failed",
},
remapping={"guest_transcription", "transcribed_speech"},
)

smach.StateMachine.add(
"GET_GUEST_ATTRIBUTES",
GetGuestAttributes(),
transitions={
"succeeded": "succeeded",
"failed": "failed",
},
)


if __name__ == "__main__":
rospy.init_node("receptionist")
Expand Down

0 comments on commit ca58f85

Please sign in to comment.