Skip to content

Commit

Permalink
Updated food detection callback groups
Browse files Browse the repository at this point in the history
  • Loading branch information
amalnanavati committed Sep 15, 2023
1 parent 4084552 commit d170560
Showing 1 changed file with 6 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
import rclpy
from rclpy.action import ActionServer, CancelResponse, GoalResponse
from rclpy.action.server import ServerGoalHandle
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
from rclpy.executors import MultiThreadedExecutor
from rclpy.node import Node
from rclpy.parameter import Parameter
Expand Down Expand Up @@ -58,8 +59,6 @@ def __init__(self) -> None:

super().__init__("segment_from_point")

self._default_callback_group = rclpy.callback_groups.ReentrantCallbackGroup()

# Check if cuda is available
self.device = "cuda" if torch.cuda.is_available() else "cpu"

Expand Down Expand Up @@ -91,6 +90,7 @@ def __init__(self) -> None:
"~/camera_info",
self.camera_info_callback,
1,
callback_group=MutuallyExclusiveCallbackGroup(),
)
self.camera_info = None
self.camera_info_lock = threading.Lock()
Expand All @@ -106,6 +106,7 @@ def __init__(self) -> None:
aligned_depth_topic,
self.depth_image_callback,
1,
callback_group=MutuallyExclusiveCallbackGroup(),
)
self.latest_depth_img_msg = None
self.latest_depth_img_msg_lock = threading.Lock()
Expand All @@ -117,6 +118,7 @@ def __init__(self) -> None:
image_topic,
self.image_callback,
1,
callback_group=MutuallyExclusiveCallbackGroup(),
)
self.latest_img_msg = None
self.latest_img_msg_lock = threading.Lock()
Expand Down Expand Up @@ -244,6 +246,7 @@ def initialize_food_segmentation(self, model_name: str, model_path: str) -> None
self.execute_callback,
goal_callback=self.goal_callback,
cancel_callback=self.cancel_callback,
callback_group=MutuallyExclusiveCallbackGroup(),
)
self.get_logger().info("...Done!")

Expand Down Expand Up @@ -509,7 +512,7 @@ def main(args=None):
segment_from_point = SegmentFromPointNode()

# Use a MultiThreadedExecutor to enable processing goals concurrently
executor = MultiThreadedExecutor()
executor = MultiThreadedExecutor(num_threads=5)

rclpy.spin(segment_from_point, executor=executor)

Expand Down

0 comments on commit d170560

Please sign in to comment.