Skip to content

Commit 4cc3acc

Browse files
authored
Revamp Callback Groups (#92)
* Put MoveIt2 objects into their own ReentrantCallbackGroup * Revert create_action_servers.py default callback group to MutuallyExclusive * Updated watchdog callback groups * Updated face detection callback groups * Updated food detection callback groups * Updated republisher callback groups
1 parent b384040 commit 4cc3acc

File tree

9 files changed

+56
-16
lines changed

9 files changed

+56
-16
lines changed

ada_feeding/ada_feeding/behaviors/move_to.py

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
import py_trees
1616
from pymoveit2 import MoveIt2, MoveIt2State
1717
from pymoveit2.robots import kinova
18+
from rclpy.callback_groups import ReentrantCallbackGroup
1819
from rclpy.node import Node
1920
from rclpy.qos import QoSPresetProfiles
2021
from sensor_msgs.msg import JointState
@@ -120,12 +121,16 @@ def __init__(
120121
# Create MoveIt 2 interface for moving the Jaco arm. This must be done
121122
# in __init__ and not setup since the MoveIt2 interface must be
122123
# initialized before the ROS2 node starts spinning.
124+
# Using ReentrantCallbackGroup to align with the examples from pymoveit2.
125+
# TODO: Assess whether ReentrantCallbackGroup is necessary for MoveIt2.
126+
callback_group = ReentrantCallbackGroup()
123127
self.moveit2 = MoveIt2(
124128
node=self.node,
125129
joint_names=kinova.joint_names(),
126130
base_link_name=kinova.base_link_name(),
127131
end_effector_name="forkTip",
128132
group_name=kinova.MOVE_GROUP_ARM,
133+
callback_group=callback_group,
129134
)
130135

131136
# Subscribe to the joint state and track the distance to goal while the

ada_feeding/ada_feeding/behaviors/toggle_collision_object.py

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
import py_trees
1313
from pymoveit2 import MoveIt2
1414
from pymoveit2.robots import kinova
15+
from rclpy.callback_groups import ReentrantCallbackGroup
1516
from rclpy.node import Node
1617

1718
# Local imports
@@ -55,12 +56,16 @@ def __init__(
5556
# Create MoveIt 2 interface for moving the Jaco arm. This must be done
5657
# in __init__ and not setup since the MoveIt2 interface must be
5758
# initialized before the ROS2 node starts spinning.
59+
# Using ReentrantCallbackGroup to align with the examples from pymoveit2.
60+
# TODO: Assess whether ReentrantCallbackGroup is necessary for MoveIt2.
61+
callback_group = ReentrantCallbackGroup()
5862
self.moveit2 = MoveIt2(
5963
node=self.node,
6064
joint_names=kinova.joint_names(),
6165
base_link_name=kinova.base_link_name(),
6266
end_effector_name="forkTip",
6367
group_name=kinova.MOVE_GROUP_ARM,
68+
callback_group=callback_group,
6469
)
6570

6671
def update(self) -> py_trees.common.Status:

ada_feeding/ada_feeding/watchdog/ft_sensor_condition.py

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -67,11 +67,15 @@ def __init__(self, node: Node) -> None:
6767

6868
# Subscribe to the FT sensor topic
6969
self.ft_sensor_topic = self._node.resolve_topic_name("~/ft_topic")
70+
self.ft_sensor_callback_group = (
71+
rclpy.callback_groups.MutuallyExclusiveCallbackGroup()
72+
)
7073
self.ft_sensor_subscription = self._node.create_subscription(
7174
WrenchStamped,
7275
self.ft_sensor_topic,
7376
self.__ft_sensor_callback,
7477
rclpy.qos.QoSPresetProfiles.SENSOR_DATA.value,
78+
callback_group=self.ft_sensor_callback_group,
7579
)
7680

7781
def __ft_sensor_callback(self, msg: WrenchStamped) -> None:

ada_feeding/scripts/ada_planning_scene.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,8 @@ def __init__(self) -> None:
5555
self.load_parameters()
5656

5757
# Initialize the MoveIt2 interface
58+
# Using ReentrantCallbackGroup to align with the examples from pymoveit2.
59+
# TODO: Assess whether ReentrantCallbackGroup is necessary for MoveIt2.
5860
callback_group = ReentrantCallbackGroup()
5961
self.moveit2 = MoveIt2(
6062
node=self,

ada_feeding/scripts/ada_watchdog.py

Lines changed: 10 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -66,8 +66,16 @@ def __init__(self) -> None:
6666
)
6767

6868
# Publish at the specified rate
69+
# TODO: Consider making this a separate thread that runs at a fixed rate,
70+
# to avoid the callback queue getting backed up if the function takes
71+
# longer than the specified rate to run.
72+
self.timer_callback_group = (
73+
rclpy.callback_groups.MutuallyExclusiveCallbackGroup()
74+
)
6975
timer_period = 1.0 / self.publish_rate_hz.value # seconds
70-
self.timer = self.create_timer(timer_period, self.__check_conditions)
76+
self.timer = self.create_timer(
77+
timer_period, self.__check_conditions, self.timer_callback_group
78+
)
7179

7280
def __load_parameters(self) -> None:
7381
"""
@@ -199,7 +207,7 @@ def main(args=None):
199207
rclpy.init(args=args)
200208

201209
# Use a MultiThreadedExecutor to enable processing topics concurrently
202-
executor = MultiThreadedExecutor()
210+
executor = MultiThreadedExecutor(num_threads=3)
203211

204212
# Create and spin the node
205213
ada_watchdog = ADAWatchdog()

ada_feeding/scripts/create_action_servers.py

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -89,8 +89,6 @@ def __init__(self) -> None:
8989
"""
9090
super().__init__("create_action_servers")
9191

92-
self._default_callback_group = rclpy.callback_groups.ReentrantCallbackGroup()
93-
9492
# Read the parameters that specify what action servers to create.
9593
action_server_params = self.read_params()
9694

ada_feeding_perception/ada_feeding_perception/face_detection.py

Lines changed: 21 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
from geometry_msgs.msg import Point
1818
import numpy as np
1919
import rclpy
20+
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
2021
from rclpy.node import Node
2122
from rclpy.parameter import Parameter
2223
from rclpy.executors import MultiThreadedExecutor
@@ -55,8 +56,6 @@ def __init__(
5556
"""
5657
super().__init__("face_detection")
5758

58-
self._default_callback_group = rclpy.callback_groups.ReentrantCallbackGroup()
59-
6059
# Read the parameters
6160
# NOTE: These parameters are only read once. Any changes after the node
6261
# is initialized will not be reflected.
@@ -108,6 +107,7 @@ def __init__(
108107
SetBool,
109108
"~/toggle_face_detection",
110109
self.toggle_face_detection_callback,
110+
callback_group=MutuallyExclusiveCallbackGroup(),
111111
)
112112

113113
# Create the publishers
@@ -131,7 +131,11 @@ def __init__(
131131
self.latest_img_msg_lock = threading.Lock()
132132
image_topic = "~/image"
133133
self.img_subscription = self.create_subscription(
134-
get_img_msg_type(image_topic, self), image_topic, self.camera_callback, 1
134+
get_img_msg_type(image_topic, self),
135+
image_topic,
136+
self.camera_callback,
137+
1,
138+
callback_group=MutuallyExclusiveCallbackGroup(),
135139
)
136140

137141
depth_buffer_size = depth_buffer_size.value
@@ -144,6 +148,7 @@ def __init__(
144148
aligned_depth_topic,
145149
self.depth_callback,
146150
1,
151+
callback_group=MutuallyExclusiveCallbackGroup(),
147152
)
148153

149154
# Subscribe to the camera info
@@ -152,7 +157,11 @@ def __init__(
152157
# (updated with subscription)
153158
self.camera_matrix = [614, 0, 312, 0, 614, 223, 0, 0, 1]
154159
self.camera_info_subscription = self.create_subscription(
155-
CameraInfo, "~/camera_info", self.camera_info_callback, 1
160+
CameraInfo,
161+
"~/camera_info",
162+
self.camera_info_callback,
163+
1,
164+
callback_group=MutuallyExclusiveCallbackGroup(),
156165
)
157166

158167
def read_params(
@@ -504,7 +513,9 @@ def run(self) -> None:
504513
with self.latest_img_msg_lock:
505514
rgb_msg = self.latest_img_msg
506515
if rgb_msg is None:
507-
self.get_logger().warn("No RGB image message received.", throttle_duration_sec=1)
516+
self.get_logger().warn(
517+
"No RGB image message received.", throttle_duration_sec=1
518+
)
508519
continue
509520

510521
# Detect the largest face in the RGB image
@@ -522,8 +533,10 @@ def run(self) -> None:
522533
if is_face_detected_depth:
523534
# Get the 3d location of the mouth
524535
face_detection_msg.detected_mouth_center.header = rgb_msg.header
525-
face_detection_msg.detected_mouth_center.point = self.get_stomion_point(
526-
img_mouth_center[0], img_mouth_center[1], depth_mm
536+
face_detection_msg.detected_mouth_center.point = (
537+
self.get_stomion_point(
538+
img_mouth_center[0], img_mouth_center[1], depth_mm
539+
)
527540
)
528541
else:
529542
is_face_detected = False
@@ -540,7 +553,7 @@ def main(args=None):
540553
rclpy.init(args=args)
541554

542555
face_detection = FaceDetectionNode()
543-
executor = MultiThreadedExecutor()
556+
executor = MultiThreadedExecutor(num_threads=4)
544557

545558
# Spin in the background since detecting faces will block
546559
# the main thread

ada_feeding_perception/ada_feeding_perception/republisher.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
# Third-party imports
1616
from rcl_interfaces.msg import ParameterDescriptor, ParameterType
1717
import rclpy
18+
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
1819
from rclpy.executors import MultiThreadedExecutor
1920
from rclpy.node import Node
2021

@@ -79,6 +80,7 @@ def __init__(self) -> None:
7980
topic=self.from_topics[i],
8081
callback=callback,
8182
qos_profile=1, # TODO: we should get and mirror the QOS profile of the from_topic
83+
callback_group=MutuallyExclusiveCallbackGroup(),
8284
)
8385
self.subs.append(subscriber)
8486

@@ -183,7 +185,7 @@ def main(args=None):
183185
republisher = Republisher()
184186

185187
# Use a MultiThreadedExecutor to enable processing goals concurrently
186-
executor = MultiThreadedExecutor()
188+
executor = MultiThreadedExecutor(num_threads=len(republisher.subs))
187189

188190
rclpy.spin(republisher, executor=executor)
189191

ada_feeding_perception/ada_feeding_perception/segment_from_point.py

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
import rclpy
1919
from rclpy.action import ActionServer, CancelResponse, GoalResponse
2020
from rclpy.action.server import ServerGoalHandle
21+
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
2122
from rclpy.executors import MultiThreadedExecutor
2223
from rclpy.node import Node
2324
from rclpy.parameter import Parameter
@@ -58,8 +59,6 @@ def __init__(self) -> None:
5859

5960
super().__init__("segment_from_point")
6061

61-
self._default_callback_group = rclpy.callback_groups.ReentrantCallbackGroup()
62-
6362
# Check if cuda is available
6463
self.device = "cuda" if torch.cuda.is_available() else "cpu"
6564

@@ -91,6 +90,7 @@ def __init__(self) -> None:
9190
"~/camera_info",
9291
self.camera_info_callback,
9392
1,
93+
callback_group=MutuallyExclusiveCallbackGroup(),
9494
)
9595
self.camera_info = None
9696
self.camera_info_lock = threading.Lock()
@@ -106,6 +106,7 @@ def __init__(self) -> None:
106106
aligned_depth_topic,
107107
self.depth_image_callback,
108108
1,
109+
callback_group=MutuallyExclusiveCallbackGroup(),
109110
)
110111
self.latest_depth_img_msg = None
111112
self.latest_depth_img_msg_lock = threading.Lock()
@@ -117,6 +118,7 @@ def __init__(self) -> None:
117118
image_topic,
118119
self.image_callback,
119120
1,
121+
callback_group=MutuallyExclusiveCallbackGroup(),
120122
)
121123
self.latest_img_msg = None
122124
self.latest_img_msg_lock = threading.Lock()
@@ -244,6 +246,7 @@ def initialize_food_segmentation(self, model_name: str, model_path: str) -> None
244246
self.execute_callback,
245247
goal_callback=self.goal_callback,
246248
cancel_callback=self.cancel_callback,
249+
callback_group=MutuallyExclusiveCallbackGroup(),
247250
)
248251
self.get_logger().info("...Done!")
249252

@@ -509,7 +512,7 @@ def main(args=None):
509512
segment_from_point = SegmentFromPointNode()
510513

511514
# Use a MultiThreadedExecutor to enable processing goals concurrently
512-
executor = MultiThreadedExecutor()
515+
executor = MultiThreadedExecutor(num_threads=5)
513516

514517
rclpy.spin(segment_from_point, executor=executor)
515518

0 commit comments

Comments
 (0)