Skip to content

Commit 1264852

Browse files
authored
Allow for Simulating Acquisition (#124)
* Update dummy SegmentFromPoint to publish new Mask.msg * Update AcquireFood goal request pickles to have the new Mask.msg * Update README with instructions on simulating bite acquisition
1 parent 1a466cb commit 1264852

11 files changed

+120
-37
lines changed

feeding_web_app_ros2_test/README.md

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,3 +17,18 @@ You can also toggle off certain combinations of dummy nodes with arguments:
1717
- **Don't run the RealSense node**: `ros2 launch feeding_web_app_ros2_test feeding_web_app_dummy_nodes_launch.xml run_real_sense:=false`
1818

1919
You can also combine any of the above arguments.
20+
21+
## Simulating an AcquireFood Goal
22+
23+
If you launch the code in `--sim mock` (see [here](https://github.com/personalrobotics/ada_feeding/blob/ros2-devel/README.md)), using bite selection through the app should properly call AcquireFood, and you should be able to see the acquisition action in RVIZ (it is recommended to add an `Axes` visualization to RVIZ for the `food` frame to see the perceived top-center and orientation of the detected food item). However, this approach has two downsides:
24+
1. The detected food mask is a dummy mask, not a real output of SegmentAnything.
25+
2. Each time you use the app to invoke AcquireFood, the mask and depth will be slightly different, which is a challenge for repeatability.
26+
27+
To address these issues, we have pickled goal request(s) from the app to the AcquireFood action. These goal request(s) were Segmented by the actual `SegmentFromPoint` node with the dummy RGB and depth images (found in `./data`). To invoke bite acquisition with this static goal request, do the following:
28+
1. `cd ~/colcon_ws`
29+
2. `python3 src/ada_feeding/start-py --sim mock`. See [here](https://github.com/personalrobotics/ada_feeding/blob/ros2-devel/README.md) for more info.
30+
3. `ros2 launch feeding_web_app_ros2_test feeding_dummy_acquirefood_launch.py`. This will have the robot move above the plate, and then invoke `AcquireFood` for the stored goal request.
31+
32+
There are 6 pickled goal requests in `./data`. You can modify which gets run through a launch argument to `feeding_dummy_acquirefood_launch.py`. Be sure to also change the images published by the DummyRealSense node to correspond to the new pickled goal request; these can be changed by launch argument to `feeding_web_app_dummy_nodes_launch.xml`.
33+
34+
To pickle more goal_requests, modify `ada_feeding/config/` to [pass the `pickle_goal_path` parameter to the AcquireFood tree](https://github.com/personalrobotics/ada_feeding/blob/f889fe44351ec552e945ba028d4928826ee03710/ada_feeding/config/ada_feeding_action_servers_default.yaml#L54). That should be a full path to where you want to store the pickle. Then, run the **dummy RealSense node**, the **real** perception nodes, run the web app, do bite selection for a bite, and select a mask. That mask will be stored in a pickle.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.

feeding_web_app_ros2_test/feeding_web_app_ros2_test/AcquireFoodClient.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,7 @@ def main(args=None):
6565
action_client.get_logger().error("MoveAbovePlate Failed")
6666
return
6767

68+
# Second, send the acquire food action
6869
# Send Goal
6970
future = action_client.acquire_food()
7071
rclpy.spin_until_future_complete(action_client, future)

feeding_web_app_ros2_test/feeding_web_app_ros2_test/SegmentFromPoint.py

Lines changed: 84 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99
from rclpy.action import ActionServer, CancelResponse, GoalResponse
1010
from rclpy.executors import MultiThreadedExecutor
1111
from rclpy.node import Node
12-
from sensor_msgs.msg import CompressedImage, RegionOfInterest
12+
from sensor_msgs.msg import CompressedImage, Image, RegionOfInterest, CameraInfo
1313
from shapely.geometry import MultiPoint
1414
import threading
1515
import time
@@ -42,9 +42,36 @@ def __init__(self, sleep_time=2.0, send_feedback_hz=10):
4242
self.latest_img_msg = None
4343
self.latest_img_msg_lock = threading.Lock()
4444

45+
# Subscribe to the depth topic, to store the latest image
46+
self.depth_subscriber = self.create_subscription(
47+
Image,
48+
"/camera/aligned_depth_to_color/image_raw",
49+
self.depth_callback,
50+
1,
51+
)
52+
self.latest_depth_msg = None
53+
self.latest_depth_msg_lock = threading.Lock()
54+
55+
# Subscribe to the camera info
56+
self.camera_info_subscriber = self.create_subscription(
57+
CameraInfo, "/camera/color/camera_info", self.camera_info_callback, 1
58+
)
59+
self.camera_info = None
60+
self.camera_info_lock = threading.Lock()
61+
4562
# Convert between ROS and CV images
4663
self.bridge = CvBridge()
4764

65+
# Create the action server
66+
self._action_server = ActionServer(
67+
self,
68+
SegmentFromPoint,
69+
"SegmentFromPoint",
70+
self.execute_callback,
71+
goal_callback=self.goal_callback,
72+
cancel_callback=self.cancel_callback,
73+
)
74+
4875
def image_callback(self, msg):
4976
"""
5077
Store the latest image message.
@@ -54,20 +81,30 @@ def image_callback(self, msg):
5481
msg: The image message.
5582
"""
5683
with self.latest_img_msg_lock:
57-
# Only create the action server after we have received at least one
58-
# image
59-
if self.latest_img_msg is None:
60-
# Create the action server
61-
self._action_server = ActionServer(
62-
self,
63-
SegmentFromPoint,
64-
"SegmentFromPoint",
65-
self.execute_callback,
66-
goal_callback=self.goal_callback,
67-
cancel_callback=self.cancel_callback,
68-
)
6984
self.latest_img_msg = msg
7085

86+
def depth_callback(self, msg):
87+
"""
88+
Store the latest depth message.
89+
90+
Parameters
91+
----------
92+
msg: The depth message.
93+
"""
94+
with self.latest_depth_msg_lock:
95+
self.latest_depth_msg = msg
96+
97+
def camera_info_callback(self, msg):
98+
"""
99+
Store the latest camera info message.
100+
101+
Parameters
102+
----------
103+
msg: The camera info message.
104+
"""
105+
with self.camera_info_lock:
106+
self.camera_info = msg
107+
71108
def goal_callback(self, goal_request):
72109
"""
73110
Accept a goal if this action does not already have an active goal,
@@ -85,12 +122,28 @@ def goal_callback(self, goal_request):
85122
goal_request: The goal request message.
86123
"""
87124
self.get_logger().info("Received goal request")
88-
if self.active_goal_request is None:
89-
self.get_logger().info("Accepting goal request")
90-
self.active_goal_request = goal_request
91-
return GoalResponse.ACCEPT
92-
self.get_logger().info("Rejecting goal request")
93-
return GoalResponse.REJECT
125+
126+
# Reject if there is already an active goal
127+
if self.active_goal_request is not None:
128+
self.get_logger().info("Rejecting goal request")
129+
return GoalResponse.REJECT
130+
131+
# Reject if this node has not received an RGB and depth image
132+
with self.latest_img_msg_lock:
133+
with self.latest_depth_msg_lock:
134+
with self.camera_info_lock:
135+
if (
136+
self.latest_img_msg is None
137+
or self.latest_depth_msg is None
138+
or self.camera_info is None
139+
):
140+
self.get_logger().info("Rejecting cancel request")
141+
return CancelResponse.REJECT
142+
143+
# Otherwise accept
144+
self.get_logger().info("Accepting goal request")
145+
self.active_goal_request = goal_request
146+
return GoalResponse.ACCEPT
94147

95148
def cancel_callback(self, goal_handle):
96149
"""
@@ -122,9 +175,15 @@ def segment_image(self, seed_point, result, segmentation_success):
122175
latest_img_msg = None
123176
with self.latest_img_msg_lock:
124177
latest_img_msg = self.latest_img_msg
178+
with self.latest_depth_msg_lock:
179+
latest_depth_msg = self.latest_depth_msg
180+
with self.camera_info_lock:
181+
camera_info = self.camera_info
125182
result.header = latest_img_msg.header
183+
result.camera_info = camera_info
126184
img = self.bridge.compressed_imgmsg_to_cv2(latest_img_msg, "bgr8")
127185
width, height, _ = img.shape
186+
depth_img = self.bridge.imgmsg_to_cv2(latest_depth_msg, "passthrough")
128187

129188
# Sleep (dummy segmentation)
130189
time.sleep(self.sleep_time)
@@ -179,6 +238,12 @@ def segment_image(self, seed_point, result, segmentation_success):
179238
format="jpeg",
180239
data=cv2.imencode(".jpg", img[y_min:y_max, x_min:x_max])[1].tostring(),
181240
)
241+
mask_msg.depth_image = self.bridge.cv2_to_imgmsg(
242+
depth_img[y_min:y_max, x_min:x_max], "passthrough"
243+
)
244+
mask_msg.average_depth = (
245+
np.median(depth_img[y_min:y_max, x_min:x_max][mask_img > 0]) / 1000.0
246+
) # Convert to meters
182247
mask_msg.item_id = "dummy_food_id_%d" % (i)
183248
mask_msg.confidence = np.random.random()
184249
result.detected_items.append(mask_msg)

feeding_web_app_ros2_test/launch/feeding_dummy_acquirefood_launch.py

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -27,23 +27,23 @@ def generate_launch_description():
2727

2828
# Initialize Arguments
2929
request = LaunchConfiguration("request")
30-
31-
# Add dummy realsense node
3230
package_prefix = FindPackageShare("feeding_web_app_ros2_test")
33-
ld.add_action(
34-
IncludeLaunchDescription(
35-
AnyLaunchDescriptionSource(
36-
[package_prefix, "/launch/feeding_web_app_dummy_nodes_launch.xml"]
37-
),
38-
launch_arguments={
39-
"run_web_bridge": "false",
40-
"run_food_detection": "false",
41-
"run_face_detection": "false",
42-
"run_motion": "false",
43-
"run_real_sense": "true",
44-
}.items(),
45-
)
46-
)
31+
32+
# # Add dummy realsense node
33+
# ld.add_action(
34+
# IncludeLaunchDescription(
35+
# AnyLaunchDescriptionSource(
36+
# [package_prefix, "/launch/feeding_web_app_dummy_nodes_launch.xml"]
37+
# ),
38+
# launch_arguments={
39+
# "run_web_bridge": "false",
40+
# "run_food_detection": "false",
41+
# "run_face_detection": "false",
42+
# "run_motion": "false",
43+
# "run_real_sense": "true",
44+
# }.items(),
45+
# )
46+
# )
4747

4848
# Add Request
4949
request_path = {

0 commit comments

Comments
 (0)