Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Receptionist - Clean-up speech recovery and get_name_and_drink #266

Merged
merged 9 commits into from
Sep 25, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -350,7 +350,11 @@ def _check_finished(self) -> bool:
)
transcription = self._transcribe_speech_client.get_result().sequence

return "yes" in transcription.lower() or "arrived" in transcription.lower() or "arrive" in transcription.lower()
return (
"yes" in transcription.lower()
or "arrived" in transcription.lower()
or "arrive" in transcription.lower()
)
return True

def _get_pose_on_path(
Expand Down
18 changes: 13 additions & 5 deletions tasks/carry_my_luggage/src/carry_my_luggage/state_machine.py
Original file line number Diff line number Diff line change
Expand Up @@ -193,19 +193,27 @@ def wait_cb(ud, msg):

def start_pose_cb(ud):
try:
ud.start_pose = rospy.wait_for_message("/robot_pose", PoseWithCovarianceStamped, timeout=rospy.Duration(5.0)).pose.pose
ud.start_pose = rospy.wait_for_message(
"/robot_pose",
PoseWithCovarianceStamped,
timeout=rospy.Duration(5.0),
).pose.pose
except rospy.ROSException:
rospy.logerr("Failed to get robot pose")
ud.start_pose = Pose(position=Point(0., 0., 0.0), orientation=Quaternion(0., 0., 0., 1.))
ud.start_pose = Pose(
position=Point(0.0, 0.0, 0.0),
orientation=Quaternion(0.0, 0.0, 0.0, 1.0),
)
return "succeeded"

smach.StateMachine.add(
"GET_START_LOCATION",
smach.CBState(
start_pose_cb,
outcomes=["succeeded"],
output_keys=["start_pose"],
),
transitions={"succeeded": "SAY_STEP"}
transitions={"succeeded": "SAY_STEP"},
)

smach.StateMachine.add(
Expand Down Expand Up @@ -261,8 +269,8 @@ def start_pose_cb(ud):
)

smach.StateMachine.add(
"GO_TO_START", # todo: instead, get the start position within the state machine, and return to it at the end
"GO_TO_START", # todo: instead, get the start position within the state machine, and return to it at the end
GoToLocation(),
remapping={"location" : "start_pose"},
remapping={"location": "start_pose"},
transitions={"succeeded": "succeeded", "failed": "succeeded"},
)
123 changes: 120 additions & 3 deletions tasks/gpsr/src/gpsr/states/object_comparison.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,16 +19,133 @@ class ObjectComparison(smach.StateMachine):

# TODO: fill this in

_smallest_list: List[str] = ["dishwasher_tab", "candle", "strawberry", "tictac", "plum", "lemon", "pear", "peach", "orange", "apple", "sponges", "fork", "knife", "spoon", "banana", "dubbelfris", "cola", "ice_tea", "fanta", "milk", "pea_soup", "sausages", "cup", "stroopwafel", "soap", "curry", "water", "crisps", "liquorice", "candy", "hagelslag", "pancake_mix", "mayonaise", "bowl", "plate", "washcloth", "pringles", "big_coke" ]
_smallest_list: List[str] = [
"dishwasher_tab",
"candle",
"strawberry",
"tictac",
"plum",
"lemon",
"pear",
"peach",
"orange",
"apple",
"sponges",
"fork",
"knife",
"spoon",
"banana",
"dubbelfris",
"cola",
"ice_tea",
"fanta",
"milk",
"pea_soup",
"sausages",
"cup",
"stroopwafel",
"soap",
"curry",
"water",
"crisps",
"liquorice",
"candy",
"hagelslag",
"pancake_mix",
"mayonaise",
"bowl",
"plate",
"washcloth",
"pringles",
"big_coke",
]
_biggest_list: List[str] = reversed(_smallest_list)

_largest_list: List[str] = _biggest_list

_heaviest_list: List[str] = ["big_coke", "pea_soup", "milk", "mayonaise", "cola", "ice_tea", "fanta", "dubbelfris", "water", "pancake_mix", "curry", "soap", "sausages", "apple", "orange", "peach", "pear", "lemon", "plum", "banana", "stroopwafel", "cup", "bowl", "plate", "washcloth", "sponges", "pringles", "crisps", "hagelslag", "liquorice", "candy", "knife", "fork", "spoon", "candle", "strawberry", "tictac", "dishwasher_tab"]
_heaviest_list: List[str] = [
"big_coke",
"pea_soup",
"milk",
"mayonaise",
"cola",
"ice_tea",
"fanta",
"dubbelfris",
"water",
"pancake_mix",
"curry",
"soap",
"sausages",
"apple",
"orange",
"peach",
"pear",
"lemon",
"plum",
"banana",
"stroopwafel",
"cup",
"bowl",
"plate",
"washcloth",
"sponges",
"pringles",
"crisps",
"hagelslag",
"liquorice",
"candy",
"knife",
"fork",
"spoon",
"candle",
"strawberry",
"tictac",
"dishwasher_tab",
]

_lightest_list: List[str] = reversed(_heaviest_list)

_thinnest_list: List[str] = ["knife", "fork", "spoon", "candle", "strawberry", "tictac", "dishwasher_tab", "liquorice", "candy", "crisps", "stroopwafel", "soap", "sponges", "washcloth", "plate", "bowl", "cup", "pancake_mix", "hagelslag", "curry", "mayonaise", "pea_soup", "sausages", "milk", "water", "dubbelfris", "cola", "ice_tea", "fanta", "big_coke", "apple", "orange", "peach", "pear", "lemon", "plum", "banana", "pringles"]
_thinnest_list: List[str] = [
"knife",
"fork",
"spoon",
"candle",
"strawberry",
"tictac",
"dishwasher_tab",
"liquorice",
"candy",
"crisps",
"stroopwafel",
"soap",
"sponges",
"washcloth",
"plate",
"bowl",
"cup",
"pancake_mix",
"hagelslag",
"curry",
"mayonaise",
"pea_soup",
"sausages",
"milk",
"water",
"dubbelfris",
"cola",
"ice_tea",
"fanta",
"big_coke",
"apple",
"orange",
"peach",
"pear",
"lemon",
"plum",
"banana",
"pringles",
]

_query: Literal[
"biggest", "largest", "smallest", "heaviest", "lightest", "thinnest"
Expand Down
48 changes: 0 additions & 48 deletions tasks/receptionist/src/receptionist/states/get_name_and_drink.py
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,6 @@ def execute(self, userdata: UserData) -> str:

return outcome


class PostRecoveryDecision(smach.State):
def __init__(
self,
Expand All @@ -96,7 +95,6 @@ def __init__(
self._possible_names = [name.lower() for name in prior_data["names"]]
self._possible_drinks = [drink.lower() for drink in prior_data["drinks"]]


def execute(self, userdata: UserData) -> str:
if not self._recovery_name_and_drink_required(userdata):
if userdata.guest_data[self._guest_id]["name"] == "unknown":
Expand All @@ -107,7 +105,6 @@ def execute(self, userdata: UserData) -> str:
outcome = "failed"
return outcome


def _recovery_name_and_drink_required(self, userdata: UserData) -> bool:
"""Determine whether both the name and drink requires recovery.

Expand All @@ -126,11 +123,6 @@ def __init__(
last_resort: bool,
param_key: str = "/receptionist/priors",
):
self,
guest_id: str,
last_resort: bool,
param_key: str = "/receptionist/priors",
):

self._guest_id = guest_id
self._param_key = param_key
Expand Down Expand Up @@ -170,43 +162,3 @@ def __init__(
"failed_drink": "failed_drink",
},
)

def __init__(
self,
guest_id: str,
last_resort: bool,
param_key: str = "/receptionist/priors",
):

self._guest_id = guest_id
self._param_key = param_key
self._last_resort = last_resort

smach.StateMachine.__init__(
self,
outcomes=["succeeded", "failed", "failed_name", "failed_drink"],
input_keys=["guest_transcription", "guest_data"],
output_keys=["guest_data", "guest_transcription"],

)
with self:

smach.StateMachine.add(
"PARSE_NAME_AND_DRINK",
self.ParseNameAndDrink(guest_id=self._guest_id, param_key=self._param_key),
transitions={"succeeded": "succeeded", "failed": "SPEECH_RECOVERY"},
)
smach.StateMachine.add(
"SPEECH_RECOVERY",
SpeechRecovery(self._guest_id, self._last_resort),
transitions={"succeeded": "succeeded", "failed": "POST_RECOVERY_DECISION"},
)
smach.StateMachine.add(
"POST_RECOVERY_DECISION",
self.PostRecoveryDecision(guest_id=self._guest_id, param_key=self._param_key),
transitions={
"failed": "failed",
"failed_name": "failed_name",
"failed_drink": "failed_drink",
},
)
Loading
Loading