17
17
from geometry_msgs .msg import Point
18
18
import numpy as np
19
19
import rclpy
20
+ from rclpy .callback_groups import MutuallyExclusiveCallbackGroup
20
21
from rclpy .node import Node
21
22
from rclpy .parameter import Parameter
22
23
from rclpy .executors import MultiThreadedExecutor
@@ -55,8 +56,6 @@ def __init__(
55
56
"""
56
57
super ().__init__ ("face_detection" )
57
58
58
- self ._default_callback_group = rclpy .callback_groups .ReentrantCallbackGroup ()
59
-
60
59
# Read the parameters
61
60
# NOTE: These parameters are only read once. Any changes after the node
62
61
# is initialized will not be reflected.
@@ -108,6 +107,7 @@ def __init__(
108
107
SetBool ,
109
108
"~/toggle_face_detection" ,
110
109
self .toggle_face_detection_callback ,
110
+ callback_group = MutuallyExclusiveCallbackGroup (),
111
111
)
112
112
113
113
# Create the publishers
@@ -131,7 +131,11 @@ def __init__(
131
131
self .latest_img_msg_lock = threading .Lock ()
132
132
image_topic = "~/image"
133
133
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 (),
135
139
)
136
140
137
141
depth_buffer_size = depth_buffer_size .value
@@ -144,6 +148,7 @@ def __init__(
144
148
aligned_depth_topic ,
145
149
self .depth_callback ,
146
150
1 ,
151
+ callback_group = MutuallyExclusiveCallbackGroup (),
147
152
)
148
153
149
154
# Subscribe to the camera info
@@ -152,7 +157,11 @@ def __init__(
152
157
# (updated with subscription)
153
158
self .camera_matrix = [614 , 0 , 312 , 0 , 614 , 223 , 0 , 0 , 1 ]
154
159
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 (),
156
165
)
157
166
158
167
def read_params (
@@ -504,7 +513,9 @@ def run(self) -> None:
504
513
with self .latest_img_msg_lock :
505
514
rgb_msg = self .latest_img_msg
506
515
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
+ )
508
519
continue
509
520
510
521
# Detect the largest face in the RGB image
@@ -522,8 +533,10 @@ def run(self) -> None:
522
533
if is_face_detected_depth :
523
534
# Get the 3d location of the mouth
524
535
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
+ )
527
540
)
528
541
else :
529
542
is_face_detected = False
@@ -540,7 +553,7 @@ def main(args=None):
540
553
rclpy .init (args = args )
541
554
542
555
face_detection = FaceDetectionNode ()
543
- executor = MultiThreadedExecutor ()
556
+ executor = MultiThreadedExecutor (num_threads = 4 )
544
557
545
558
# Spin in the background since detecting faces will block
546
559
# the main thread
0 commit comments