From c3115917cf564852e05e94bb7bea1b5451e9dabf Mon Sep 17 00:00:00 2001 From: Jelmer de Wolde Date: Fri, 3 Jan 2025 14:48:31 +0000 Subject: [PATCH] Remove node from node names. Signed-off-by: Jelmer de Wolde --- .../src_py/get_mask_properties.py | 12 +++++------- .../src_py/get_rgbd_from_topic.py | 12 +++++------- .../rcdt_detection/src_py/pose_from_pixel.py | 12 +++++------- .../src/rcdt_detection/src_py/publish_image.py | 12 +++++------- .../src/rcdt_detection/src_py/publish_masks.py | 12 +++++------- .../src/rcdt_detection/src_py/segment_image.py | 12 +++++------- .../src_py/select_image_from_list.py | 18 ++++++------------ .../src_py/select_pick_location.py | 12 +++++------- .../src_py/combine_camera_topics.py | 4 ++-- .../src_py/convert_32FC1_to_16UC1.py | 4 ++-- .../src/rcdt_utilities/src_py/joy_to_twist.py | 4 ++-- .../rcdt_utilities/src_py/manipulate_pose.py | 4 ++-- .../rcdt_utilities/src_py/moveit_controller.py | 4 ++-- 13 files changed, 51 insertions(+), 71 deletions(-) diff --git a/ros2_ws/src/rcdt_detection/src_py/get_mask_properties.py b/ros2_ws/src/rcdt_detection/src_py/get_mask_properties.py index 3947f9c..f08c262 100755 --- a/ros2_ws/src/rcdt_detection/src_py/get_mask_properties.py +++ b/ros2_ws/src/rcdt_detection/src_py/get_mask_properties.py @@ -11,21 +11,19 @@ from vision_msgs.msg import Point2D -from rcdt_detection_msgs.srv import GetMaskProperties +from rcdt_detection_msgs.srv import GetMaskProperties as Srv from rcdt_detection.mask_properties import MaskProperties from rcdt_utilities.cv_utils import ros_image_to_cv2_image, camera_info_to_intrinsics ros_logger = logging.get_logger(__name__) -class GetMaskPropertiesNode(Node): +class GetMaskProperties(Node): def __init__(self) -> None: super().__init__("get_mask_properties") - self.create_service(GetMaskProperties, "/get_mask_properties", self.callback) + self.create_service(Srv, "/get_mask_properties", self.callback) - def callback( - self, request: GetMaskProperties.Request, response: GetMaskProperties.Response - ) -> GetMaskProperties.Response: + def callback(self, request: Srv.Request, response: Srv.Response) -> Srv.Response: mask = ros_image_to_cv2_image(request.mask) depth_image = ros_image_to_cv2_image(request.depth_image) intrinsics = camera_info_to_intrinsics(request.camera_info) @@ -48,7 +46,7 @@ def callback( def main(args: str = None) -> None: rclpy.init(args=args) - node = GetMaskPropertiesNode() + node = GetMaskProperties() spin_node(node) diff --git a/ros2_ws/src/rcdt_detection/src_py/get_rgbd_from_topic.py b/ros2_ws/src/rcdt_detection/src_py/get_rgbd_from_topic.py index f18223e..d0b990b 100755 --- a/ros2_ws/src/rcdt_detection/src_py/get_rgbd_from_topic.py +++ b/ros2_ws/src/rcdt_detection/src_py/get_rgbd_from_topic.py @@ -8,21 +8,19 @@ from rclpy import logging from rclpy.node import Node from rclpy import wait_for_message -from rcdt_detection_msgs.srv import GetRGBDFromTopic +from rcdt_detection_msgs.srv import GetRGBDFromTopic as Srv from realsense2_camera_msgs.msg import RGBD from rcdt_utilities.launch_utils import spin_node ros_logger = logging.get_logger(__name__) -class GetRGBDFromTopicNode(Node): +class GetRGBDFromTopic(Node): def __init__(self) -> None: super().__init__("get_rgbd_from_topic") - self.create_service(GetRGBDFromTopic, "/get_rgbd_from_topic", self.callback) + self.create_service(Srv, "/get_rgbd_from_topic", self.callback) - def callback( - self, request: GetRGBDFromTopic.Request, response: GetRGBDFromTopic.Response - ) -> GetRGBDFromTopic.Response: + def callback(self, request: Srv.Request, response: Srv.Response) -> Srv.Response: if request.topic == "": ros_logger.error("No topic was specified. Exit.") response.success = False @@ -43,7 +41,7 @@ def callback( def main(args: str = None) -> None: rclpy.init(args=args) - node = GetRGBDFromTopicNode() + node = GetRGBDFromTopic() spin_node(node) diff --git a/ros2_ws/src/rcdt_detection/src_py/pose_from_pixel.py b/ros2_ws/src/rcdt_detection/src_py/pose_from_pixel.py index 460ce1b..efdc534 100755 --- a/ros2_ws/src/rcdt_detection/src_py/pose_from_pixel.py +++ b/ros2_ws/src/rcdt_detection/src_py/pose_from_pixel.py @@ -10,22 +10,20 @@ from rclpy.node import Node from rcdt_utilities.launch_utils import spin_node from sensor_msgs.msg import CameraInfo -from rcdt_detection_msgs.srv import PoseFromPixel +from rcdt_detection_msgs.srv import PoseFromPixel as Srv from rcdt_utilities.cv_utils import ros_image_to_cv2_image ros_logger = logging.get_logger(__name__) -class PoseFromPixelNode(Node): +class PoseFromPixel(Node): """Converts a pixel to the corresponding pose in meters.""" def __init__(self) -> None: super().__init__("pose_from_pixel") - self.create_service(PoseFromPixel, "/pose_from_pixel", self.callback) + self.create_service(Srv, "/pose_from_pixel", self.callback) - def callback( - self, request: PoseFromPixel.Request, response: PoseFromPixel.Response - ) -> PoseFromPixel.Response: + def callback(self, request: Srv.Request, response: Srv.Response) -> Srv.Response: cv2_image = ros_image_to_cv2_image(request.depth_image) height, width = cv2_image.shape intr = calculate_intrinsics(request.camera_info) @@ -87,7 +85,7 @@ def calculate_intrinsics(camera_info: CameraInfo) -> rs2.intrinsics: def main(args: str = None) -> None: rclpy.init(args=args) - node = PoseFromPixelNode() + node = PoseFromPixel() spin_node(node) diff --git a/ros2_ws/src/rcdt_detection/src_py/publish_image.py b/ros2_ws/src/rcdt_detection/src_py/publish_image.py index 9646c1b..8bb99a2 100755 --- a/ros2_ws/src/rcdt_detection/src_py/publish_image.py +++ b/ros2_ws/src/rcdt_detection/src_py/publish_image.py @@ -8,20 +8,18 @@ from rclpy import logging from rclpy.node import Node from rcdt_utilities.launch_utils import spin_node -from rcdt_detection_msgs.srv import PublishImage +from rcdt_detection_msgs.srv import PublishImage as Srv from sensor_msgs.msg import Image ros_logger = logging.get_logger(__name__) -class PublishImageNode(Node): +class PublishImage(Node): def __init__(self) -> None: super().__init__("publish_image") - self.create_service(PublishImage, "/publish_image", self.callback) + self.create_service(Srv, "/publish_image", self.callback) - def callback( - self, request: PublishImage.Request, response: PublishImage.Response - ) -> PublishImage.Response: + def callback(self, request: Srv.Request, response: Srv.Response) -> Srv.Response: publisher = self.create_publisher(Image, request.topic, 10) publisher.publish(request.image) response.success = True @@ -30,7 +28,7 @@ def callback( def main(args: str = None) -> None: rclpy.init(args=args) - node = PublishImageNode() + node = PublishImage() spin_node(node) diff --git a/ros2_ws/src/rcdt_detection/src_py/publish_masks.py b/ros2_ws/src/rcdt_detection/src_py/publish_masks.py index 53565cb..7247f0e 100755 --- a/ros2_ws/src/rcdt_detection/src_py/publish_masks.py +++ b/ros2_ws/src/rcdt_detection/src_py/publish_masks.py @@ -9,21 +9,19 @@ from rclpy import logging from rclpy.node import Node from rcdt_utilities.launch_utils import spin_node -from rcdt_detection_msgs.srv import PublishMasks +from rcdt_detection_msgs.srv import PublishMasks as Srv from rcdt_utilities.cv_utils import cv2_image_to_ros_image, ros_image_to_cv2_image from sensor_msgs.msg import Image ros_logger = logging.get_logger(__name__) -class PublishMasksNode(Node): +class PublishMasks(Node): def __init__(self) -> None: super().__init__("publish_masks") - self.create_service(PublishMasks, "/publish_masks", self.callback) + self.create_service(Srv, "/publish_masks", self.callback) - def callback( - self, request: PublishMasks.Request, response: PublishMasks.Response - ) -> PublishMasks.Response: + def callback(self, request: Srv.Request, response: Srv.Response) -> Srv.Response: publisher = self.create_publisher(Image, request.topic, 10) masks_cv2 = [ros_image_to_cv2_image(mask) for mask in request.masks] if len(masks_cv2) == 0: @@ -37,7 +35,7 @@ def callback( def main(args: str = None) -> None: rclpy.init(args=args) - node = PublishMasksNode() + node = PublishMasks() spin_node(node) diff --git a/ros2_ws/src/rcdt_detection/src_py/segment_image.py b/ros2_ws/src/rcdt_detection/src_py/segment_image.py index ac3b379..c75534a 100755 --- a/ros2_ws/src/rcdt_detection/src_py/segment_image.py +++ b/ros2_ws/src/rcdt_detection/src_py/segment_image.py @@ -9,7 +9,7 @@ from rclpy.node import Node from rcdt_utilities.launch_utils import spin_node from rclpy import logging -from rcdt_detection_msgs.srv import SegmentImage +from rcdt_detection_msgs.srv import SegmentImage as Srv from rcdt_detection.segmentation import segment_image, load_segmentation_model from rcdt_utilities.cv_utils import cv2_image_to_ros_image, ros_image_to_cv2_image from rcdt_detection.image_manipulation import ( @@ -20,17 +20,15 @@ ros_logger = logging.get_logger(__name__) -class SegmentImageNode(Node): +class SegmentImage(Node): def __init__(self) -> None: super().__init__("segment_image") self.declare_parameter("model_name", "SAM2") model_name = self.get_parameter("model_name").get_parameter_value().string_value - self.create_service(SegmentImage, "segment_image", self.callback) + self.create_service(Srv, "segment_image", self.callback) self.model = load_segmentation_model(model_name) - def callback( - self, request: SegmentImage.Request, response: SegmentImage.Response - ) -> SegmentImage.Response: + def callback(self, request: Srv.Request, response: Srv.Response) -> Srv.Response: input_image_ros = request.input_image input_image_cv2 = ros_image_to_cv2_image(input_image_ros) @@ -54,7 +52,7 @@ def callback( def main(args: str = None) -> None: rclpy.init(args=args) - node = SegmentImageNode() + node = SegmentImage() spin_node(node) diff --git a/ros2_ws/src/rcdt_detection/src_py/select_image_from_list.py b/ros2_ws/src/rcdt_detection/src_py/select_image_from_list.py index 2cddca7..0e8348d 100755 --- a/ros2_ws/src/rcdt_detection/src_py/select_image_from_list.py +++ b/ros2_ws/src/rcdt_detection/src_py/select_image_from_list.py @@ -7,24 +7,18 @@ import rclpy from rclpy import logging from rclpy.node import Node -from rcdt_detection_msgs.srv import SelectImageFromList +from rcdt_detection_msgs.srv import SelectImageFromList as Srv from rcdt_utilities.launch_utils import spin_node ros_logger = logging.get_logger(__name__) -class SelectImageFromListNode(Node): +class SelectImageFromList(Node): def __init__(self) -> None: super().__init__("select_image_from_list") - self.create_service( - SelectImageFromList, "/select_image_from_list", self.callback - ) - - def callback( - self, - request: SelectImageFromList.Request, - response: SelectImageFromList.Response, - ) -> SelectImageFromList.Response: + self.create_service(Srv, "/select_image_from_list", self.callback) + + def callback(self, request: Srv.Request, response: Srv.Response) -> Srv.Response: n_images = len(request.image_list) n_select = request.n if n_select >= n_images: @@ -40,7 +34,7 @@ def callback( def main(args: str = None) -> None: rclpy.init(args=args) - node = SelectImageFromListNode() + node = SelectImageFromList() spin_node(node) diff --git a/ros2_ws/src/rcdt_detection/src_py/select_pick_location.py b/ros2_ws/src/rcdt_detection/src_py/select_pick_location.py index 6abe7e8..e0ec759 100755 --- a/ros2_ws/src/rcdt_detection/src_py/select_pick_location.py +++ b/ros2_ws/src/rcdt_detection/src_py/select_pick_location.py @@ -8,7 +8,7 @@ import rclpy from rclpy.node import Node from rclpy import logging -from rcdt_detection_msgs.srv import SelectPickLocation +from rcdt_detection_msgs.srv import SelectPickLocation as Srv from rcdt_utilities.cv_utils import ( ros_image_to_cv2_image, cv2_image_to_ros_image, @@ -21,14 +21,12 @@ ros_logger = logging.get_logger(__name__) -class SelectPickLocationNode(Node): +class SelectPickLocation(Node): def __init__(self) -> None: super().__init__("filter_masks") - self.create_service(SelectPickLocation, "/select_pick_location", self.callback) + self.create_service(Srv, "/select_pick_location", self.callback) - def callback( - self, request: SelectPickLocation.Request, response: SelectPickLocation.Response - ) -> SelectPickLocation.Response: + def callback(self, request: Srv.Request, response: Srv.Response) -> Srv.Response: depth_image = ros_image_to_cv2_image(request.depth_image) intrinsics = camera_info_to_intrinsics(request.camera_info) @@ -65,7 +63,7 @@ def callback( def main(args: str = None) -> None: rclpy.init(args=args) - node = SelectPickLocationNode() + node = SelectPickLocation() spin_node(node) diff --git a/ros2_ws/src/rcdt_sensors/src_py/combine_camera_topics.py b/ros2_ws/src/rcdt_sensors/src_py/combine_camera_topics.py index b40f1e7..a7f2d41 100755 --- a/ros2_ws/src/rcdt_sensors/src_py/combine_camera_topics.py +++ b/ros2_ws/src/rcdt_sensors/src_py/combine_camera_topics.py @@ -14,7 +14,7 @@ ros_logger = logging.get_logger(__name__) -class CombineCameraTopicsNode(Node): +class CombineCameraTopics(Node): def __init__(self) -> bool: super().__init__("combine_camera_topics") self.declare_parameter("rgb", "/camera/camera/color/image_raw") @@ -56,7 +56,7 @@ def update_depth_info(self, msg: CameraInfo) -> None: def main(args: str = None) -> None: rclpy.init(args=args) - node = CombineCameraTopicsNode() + node = CombineCameraTopics() spin_node(node) diff --git a/ros2_ws/src/rcdt_sensors/src_py/convert_32FC1_to_16UC1.py b/ros2_ws/src/rcdt_sensors/src_py/convert_32FC1_to_16UC1.py index 612adf2..fe2c2da 100755 --- a/ros2_ws/src/rcdt_sensors/src_py/convert_32FC1_to_16UC1.py +++ b/ros2_ws/src/rcdt_sensors/src_py/convert_32FC1_to_16UC1.py @@ -15,7 +15,7 @@ ros_logger = logging.get_logger(__name__) -class Convert32FC1to16UC1Node(Node): +class Convert32FC1to16UC1(Node): def __init__(self) -> bool: super().__init__("convert_32FC1_to_16UC1_node") @@ -36,7 +36,7 @@ def callback(self, msg: Image) -> None: def main(args: str = None) -> None: rclpy.init(args=args) - node = Convert32FC1to16UC1Node() + node = Convert32FC1to16UC1() spin_node(node) diff --git a/ros2_ws/src/rcdt_utilities/src_py/joy_to_twist.py b/ros2_ws/src/rcdt_utilities/src_py/joy_to_twist.py index 2df9627..e2c93b2 100755 --- a/ros2_ws/src/rcdt_utilities/src_py/joy_to_twist.py +++ b/ros2_ws/src/rcdt_utilities/src_py/joy_to_twist.py @@ -15,7 +15,7 @@ ros_logger = logging.get_logger(__name__) -class JoyToTwistNode(Node): +class JoyToTwist(Node): def __init__(self) -> bool: super().__init__("joy_to_twist_node") self.declare_parameter("sub_topic", "/joy") @@ -81,7 +81,7 @@ def handle_input(self, sub_msg: Joy) -> None: def main(args: str = None) -> None: rclpy.init(args=args) - node = JoyToTwistNode() + node = JoyToTwist() spin_node(node) diff --git a/ros2_ws/src/rcdt_utilities/src_py/manipulate_pose.py b/ros2_ws/src/rcdt_utilities/src_py/manipulate_pose.py index 76d83ec..a11a594 100755 --- a/ros2_ws/src/rcdt_utilities/src_py/manipulate_pose.py +++ b/ros2_ws/src/rcdt_utilities/src_py/manipulate_pose.py @@ -19,7 +19,7 @@ ros_logger = logging.get_logger(__name__) -class ManipulatePoseNode(Node): +class ManipulatePose(Node): def __init__(self): super().__init__("manipulate_pose") @@ -92,7 +92,7 @@ def apply_transform_relative(pose: PoseStamped, transform: Transform) -> PoseSta def main(args: str = None) -> None: rclpy.init(args=args) - node = ManipulatePoseNode() + node = ManipulatePose() spin_node(node) diff --git a/ros2_ws/src/rcdt_utilities/src_py/moveit_controller.py b/ros2_ws/src/rcdt_utilities/src_py/moveit_controller.py index bafddcf..30c6073 100755 --- a/ros2_ws/src/rcdt_utilities/src_py/moveit_controller.py +++ b/ros2_ws/src/rcdt_utilities/src_py/moveit_controller.py @@ -26,7 +26,7 @@ from std_srvs.srv import Trigger -class MoveitControllerNode(Node): +class MoveitController(Node): def __init__(self, group: str) -> None: name = "moveit_controller" super().__init__(name) @@ -222,7 +222,7 @@ def clear_objects( def main(args: str = None) -> None: rclpy.init(args=args) executor = MultiThreadedExecutor() - node = MoveitControllerNode("fr3_arm") + node = MoveitController("fr3_arm") executor.add_node(node) spin_executor(executor)