Skip to content

Commit f0fb68a

Browse files
amalnanavatiTaylor Kessler Faulkner
andauthored
Robustness Improvements from 8/28 Pilot (#197)
* Add customized configurations * Rotate the table 90 degrees * [WIP] finalize rotated table planning scenes * Add timeouts to MoveIt2 Plan * Only create a planning scene batch if are retrying until the add is succesful * Mouth should face the forktip * Fixes from in-person testing * Better logging * Fail planning scene initialization ifthe node doesn't get the robot configurations * Adjust table detection offsets * Re-add old planning scenes, keep the 90 degrees as separate options * Add a timeout to retry_call_ros_service * Re-arrange custom params * Have actions plan deeper * Improve logging * Destroy rates after use * LinUCB shoudl return all actions, with a one-hot probability vector * Formatting * Send acquisition report info in feedback instead of result * Finish tuning planning scene for 90-degree rotated in-bed * Improve logs * Improve logs --------- Co-authored-by: Taylor Kessler Faulkner <taylorkf@cs.washington.edu>
1 parent a587c69 commit f0fb68a

30 files changed

+970
-299
lines changed

ada_feeding/ada_feeding/behaviors/acquisition/compute_action_constraints.py

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,7 @@ def blackboard_outputs(
9090
grasp_thresh: Optional[BlackboardKey], # SetParameters.Request
9191
ext_thresh: Optional[BlackboardKey], # SetParameters.Request
9292
action: Optional[BlackboardKey], # AcquisitionSchema.msg
93+
action_index: Optional[BlackboardKey], # int
9394
) -> None:
9495
"""
9596
Blackboard Outputs
@@ -135,6 +136,7 @@ def update(self) -> py_trees.common.Status:
135136
self.logger.error(f"Bad Action Select Response: {response.status}")
136137
return py_trees.common.Status.FAILURE
137138
prob = np.array(response.probabilities)
139+
self.logger.debug(f"Action Probabilities: {prob} (size {prob.size})")
138140
if (
139141
len(response.actions) == 0
140142
or len(response.actions) != len(response.probabilities)
@@ -204,6 +206,7 @@ def update(self) -> py_trees.common.Status:
204206

205207
### Final write to Blackboard
206208
self.blackboard_set("action", action)
209+
self.blackboard_set("action_index", index)
207210
return py_trees.common.Status.SUCCESS
208211

209212

ada_feeding/ada_feeding/behaviors/moveit2/moveit2_execute.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -219,3 +219,4 @@ def terminate(self, new_status: py_trees.common.Status) -> None:
219219
break
220220

221221
rate.sleep()
222+
self.node.destroy_rate(rate)

ada_feeding/ada_feeding/behaviors/ros/tf.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -433,6 +433,7 @@ def update(self) -> py_trees.common.Status:
433433
return py_trees.common.Status.FAILURE
434434

435435
# Write the transformed_msg
436+
self.logger.debug(f"Transformed message: {transformed_msg}")
436437
self.blackboard_set("transformed_msg", transformed_msg)
437438

438439
return py_trees.common.Status.SUCCESS
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
"""
2+
This subpackage contains custom py_tree behaviors for Bite Transfer.
3+
"""
4+
5+
from .compute_mouth_frame import ComputeMouthFrame
Lines changed: 193 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,193 @@
1+
#!/usr/bin/env python3
2+
# -*- coding: utf-8 -*-
3+
"""
4+
This module defines the ComputeMouthFrame behavior, which takes in the PointStamped
5+
containing the (x, y, z) position of the mouth in the camera frame, and returns the
6+
pose of the mouth in the base frame.
7+
"""
8+
9+
# Standard imports
10+
from typing import Optional, Union
11+
12+
# Third-party imports
13+
from geometry_msgs.msg import PointStamped, PoseStamped, Vector3
14+
from overrides import override
15+
import py_trees
16+
import rclpy
17+
import tf2_ros
18+
19+
# Local imports
20+
from ada_feeding.helpers import (
21+
BlackboardKey,
22+
quat_between_vectors,
23+
get_tf_object,
24+
)
25+
from ada_feeding.behaviors import BlackboardBehavior
26+
27+
28+
class ComputeMouthFrame(BlackboardBehavior):
29+
"""
30+
Compute the mouth PoseStamped in the base frame, where the position is the output
31+
of face detection and the orientation is facing the forkTip.
32+
"""
33+
34+
# pylint: disable=arguments-differ
35+
# We *intentionally* violate Liskov Substitution Princple
36+
# in that blackboard config (inputs + outputs) are not
37+
# meant to be called in a generic setting.
38+
39+
# pylint: disable=too-many-arguments
40+
# These are effectively config definitions
41+
# They require a lot of arguments.
42+
43+
def blackboard_inputs(
44+
self,
45+
detected_mouth_center: Union[BlackboardKey, PointStamped],
46+
timestamp: Union[BlackboardKey, rclpy.time.Time] = rclpy.time.Time(),
47+
world_frame: Union[BlackboardKey, str] = "root", # +z will match this frame
48+
frame_to_orient_towards: Union[
49+
BlackboardKey, str
50+
] = "forkTip", # +x will point towards this frame
51+
) -> None:
52+
"""
53+
Blackboard Inputs
54+
55+
Parameters
56+
----------
57+
detected_mouth_center : Union[BlackboardKey, PointStamped]
58+
The detected mouth center in the camera frame.
59+
timestamp : Union[BlackboardKey, rclpy.time.Time]
60+
The timestamp of the detected mouth center (default 0 for latest).
61+
world_frame : Union[BlackboardKey, str]
62+
The target frame to transform the mouth center to.
63+
frame_to_orient_towards : Union[BlackboardKey, str]
64+
The frame that the mouth should orient towards.
65+
"""
66+
# pylint: disable=unused-argument, duplicate-code
67+
# Arguments are handled generically in base class.
68+
super().blackboard_inputs(
69+
**{key: value for key, value in locals().items() if key != "self"}
70+
)
71+
72+
def blackboard_outputs(
73+
self, mouth_pose: Optional[BlackboardKey] # PoseStamped
74+
) -> None:
75+
"""
76+
Blackboard Outputs
77+
78+
Parameters
79+
----------
80+
mouth_pose : Optional[BlackboardKey]
81+
The PoseStamped of the mouth in the base frame.
82+
"""
83+
# pylint: disable=unused-argument, duplicate-code
84+
# Arguments are handled generically in base class.
85+
super().blackboard_outputs(
86+
**{key: value for key, value in locals().items() if key != "self"}
87+
)
88+
89+
@override
90+
def setup(self, **kwargs):
91+
# Docstring copied from @override
92+
93+
# pylint: disable=attribute-defined-outside-init
94+
# It is okay for attributes in behaviors to be
95+
# defined in the setup / initialise functions.
96+
97+
# Get Node from Kwargs
98+
self.node = kwargs["node"]
99+
100+
# Get TF Listener from blackboard
101+
self.tf_buffer, _, self.tf_lock = get_tf_object(self.blackboard, self.node)
102+
103+
@override
104+
def update(self) -> py_trees.common.Status:
105+
# Docstring copied from @override
106+
107+
# Validate inputs
108+
if not self.blackboard_exists(
109+
[
110+
"detected_mouth_center",
111+
"timestamp",
112+
"world_frame",
113+
"frame_to_orient_towards",
114+
]
115+
):
116+
self.logger.error(
117+
"Missing detected_mouth_center, timestamp, world_frame, or frame_to_orient_towards."
118+
)
119+
return py_trees.common.Status.FAILURE
120+
detected_mouth_center = self.blackboard_get("detected_mouth_center")
121+
timestamp = self.blackboard_get("timestamp")
122+
world_frame = self.blackboard_get("world_frame")
123+
frame_to_orient_towards = self.blackboard_get("frame_to_orient_towards")
124+
125+
# Lock TF Buffer
126+
if self.tf_lock.locked():
127+
# Not yet, wait for it
128+
# Use a Timeout decorator to determine failure.
129+
return py_trees.common.Status.RUNNING
130+
with self.tf_lock:
131+
# Transform detected_mouth_center to world_frame
132+
if not self.tf_buffer.can_transform(
133+
world_frame,
134+
detected_mouth_center.header.frame_id,
135+
timestamp,
136+
):
137+
# Not yet, wait for it
138+
# Use a Timeout decorator to determine failure.
139+
self.logger.warning("ComputeMouthFrame waiting on world/camera TF...")
140+
return py_trees.common.Status.RUNNING
141+
camera_transform = self.tf_buffer.lookup_transform(
142+
world_frame,
143+
detected_mouth_center.header.frame_id,
144+
timestamp,
145+
)
146+
mouth_point = tf2_ros.TransformRegistration().get(PointStamped)(
147+
detected_mouth_center, camera_transform
148+
)
149+
self.logger.info(f"Computed mouth point: {mouth_point.point}")
150+
151+
# Transform frame_to_orient_towards to world_frame
152+
if not self.tf_buffer.can_transform(
153+
world_frame,
154+
frame_to_orient_towards,
155+
timestamp,
156+
):
157+
# Not yet, wait for it
158+
# Use a Timeout decorator to determine failure.
159+
self.logger.warning("ComputeMouthFrame waiting on world/forkTip TF...")
160+
return py_trees.common.Status.RUNNING
161+
orientation_target_transform = self.tf_buffer.lookup_transform(
162+
world_frame,
163+
frame_to_orient_towards,
164+
timestamp,
165+
)
166+
self.logger.info(
167+
f"Computed orientation target transform: {orientation_target_transform.transform}"
168+
)
169+
170+
# Get the yaw of the face frame
171+
x_unit = Vector3(x=1.0, y=0.0, z=0.0)
172+
x_pos = Vector3(
173+
x=orientation_target_transform.transform.translation.x
174+
- mouth_point.point.x,
175+
y=orientation_target_transform.transform.translation.y
176+
- mouth_point.point.y,
177+
z=0.0,
178+
)
179+
self.logger.info(f"Computed x_pos: {x_pos}")
180+
quat = quat_between_vectors(x_unit, x_pos)
181+
self.logger.info(f"Computed orientation: {quat}")
182+
183+
# Create return object
184+
mouth_pose = PoseStamped()
185+
mouth_pose.header.frame_id = mouth_point.header.frame_id
186+
mouth_pose.header.stamp = mouth_point.header.stamp
187+
mouth_pose.pose.position = mouth_point.point
188+
mouth_pose.pose.orientation = quat
189+
190+
# Write to blackboard outputs
191+
self.blackboard_set("mouth_pose", mouth_pose)
192+
193+
return py_trees.common.Status.SUCCESS

ada_feeding/ada_feeding/idioms/retry_call_ros_service.py

Lines changed: 15 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@ def retry_call_ros_service(
2525
response_checks: Optional[List[py_trees.common.ComparisonExpression]] = None,
2626
max_retries: int = 3,
2727
wait_for_server_timeout_sec: float = 0.0,
28+
server_execution_timeout_sec: float = 10.0,
2829
) -> py_trees.behaviour.Behaviour:
2930
"""
3031
Creates a behavior that calls a ROS service and optionally checkes the response.
@@ -51,6 +52,8 @@ def retry_call_ros_service(
5152
max_retries: The maximum number of retries.
5253
wait_for_server_timeout_sec: The timeout for waiting for the server to be
5354
available.
55+
server_execution_timeout_sec: The timeout for the server to execute the request. If
56+
<= 0.0, no timeout is set.
5457
"""
5558

5659
# pylint: disable=too-many-arguments, too-many-locals
@@ -90,10 +93,20 @@ def retry_call_ros_service(
9093
key_request=key_request,
9194
)
9295

96+
# Add a timeout
97+
if server_execution_timeout_sec > 0.0:
98+
call_ros_service_wrapper = py_trees.decorators.Timeout(
99+
name=call_ros_service_behavior_name + "_timeout",
100+
child=call_ros_service_behavior,
101+
duration=server_execution_timeout_sec,
102+
)
103+
else:
104+
call_ros_service_wrapper = call_ros_service_behavior
105+
93106
# Create the check response behavior
94107
if response_checks is not None:
95108
# Add all the response checks
96-
children = [call_ros_service_behavior]
109+
children = [call_ros_service_wrapper]
97110
for i, response_check in enumerate(response_checks):
98111
check_response_behavior_name = Blackboard.separator.join(
99112
[name, check_response_namespace_prefix + str(i)]
@@ -111,7 +124,7 @@ def retry_call_ros_service(
111124
children=children,
112125
)
113126
else:
114-
child = call_ros_service_behavior
127+
child = call_ros_service_wrapper
115128

116129
# Add a retry decorator on top of the child
117130
retry_behavior = py_trees.decorators.Retry(

0 commit comments

Comments
 (0)