Skip to content

Commit

Permalink
Merge pull request #69 from alliander-opensource/remove-node-from-nod…
Browse files Browse the repository at this point in the history
…e-names

Remove node from node names.
  • Loading branch information
Jelmerdw authored Jan 3, 2025
2 parents 48e9ed6 + c311591 commit fe7f35a
Show file tree
Hide file tree
Showing 13 changed files with 51 additions and 71 deletions.
12 changes: 5 additions & 7 deletions ros2_ws/src/rcdt_detection/src_py/get_mask_properties.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -48,7 +46,7 @@ def callback(

def main(args: str = None) -> None:
rclpy.init(args=args)
node = GetMaskPropertiesNode()
node = GetMaskProperties()
spin_node(node)


Expand Down
12 changes: 5 additions & 7 deletions ros2_ws/src/rcdt_detection/src_py/get_rgbd_from_topic.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -43,7 +41,7 @@ def callback(

def main(args: str = None) -> None:
rclpy.init(args=args)
node = GetRGBDFromTopicNode()
node = GetRGBDFromTopic()
spin_node(node)


Expand Down
12 changes: 5 additions & 7 deletions ros2_ws/src/rcdt_detection/src_py/pose_from_pixel.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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)


Expand Down
12 changes: 5 additions & 7 deletions ros2_ws/src/rcdt_detection/src_py/publish_image.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -30,7 +28,7 @@ def callback(

def main(args: str = None) -> None:
rclpy.init(args=args)
node = PublishImageNode()
node = PublishImage()
spin_node(node)


Expand Down
12 changes: 5 additions & 7 deletions ros2_ws/src/rcdt_detection/src_py/publish_masks.py
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand All @@ -37,7 +35,7 @@ def callback(

def main(args: str = None) -> None:
rclpy.init(args=args)
node = PublishMasksNode()
node = PublishMasks()
spin_node(node)


Expand Down
12 changes: 5 additions & 7 deletions ros2_ws/src/rcdt_detection/src_py/segment_image.py
Original file line number Diff line number Diff line change
Expand Up @@ -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 (
Expand All @@ -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)

Expand All @@ -54,7 +52,7 @@ def callback(

def main(args: str = None) -> None:
rclpy.init(args=args)
node = SegmentImageNode()
node = SegmentImage()
spin_node(node)


Expand Down
18 changes: 6 additions & 12 deletions ros2_ws/src/rcdt_detection/src_py/select_image_from_list.py
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand All @@ -40,7 +34,7 @@ def callback(

def main(args: str = None) -> None:
rclpy.init(args=args)
node = SelectImageFromListNode()
node = SelectImageFromList()
spin_node(node)


Expand Down
12 changes: 5 additions & 7 deletions ros2_ws/src/rcdt_detection/src_py/select_pick_location.py
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand All @@ -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)

Expand Down Expand Up @@ -65,7 +63,7 @@ def callback(

def main(args: str = None) -> None:
rclpy.init(args=args)
node = SelectPickLocationNode()
node = SelectPickLocation()
spin_node(node)


Expand Down
4 changes: 2 additions & 2 deletions ros2_ws/src/rcdt_sensors/src_py/combine_camera_topics.py
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand Down Expand Up @@ -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)


Expand Down
4 changes: 2 additions & 2 deletions ros2_ws/src/rcdt_sensors/src_py/convert_32FC1_to_16UC1.py
Original file line number Diff line number Diff line change
Expand Up @@ -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")

Expand All @@ -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)


Expand Down
4 changes: 2 additions & 2 deletions ros2_ws/src/rcdt_utilities/src_py/joy_to_twist.py
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand Down Expand Up @@ -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)


Expand Down
4 changes: 2 additions & 2 deletions ros2_ws/src/rcdt_utilities/src_py/manipulate_pose.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
ros_logger = logging.get_logger(__name__)


class ManipulatePoseNode(Node):
class ManipulatePose(Node):
def __init__(self):
super().__init__("manipulate_pose")

Expand Down Expand Up @@ -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)


Expand Down
4 changes: 2 additions & 2 deletions ros2_ws/src/rcdt_utilities/src_py/moveit_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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)

Expand Down

0 comments on commit fe7f35a

Please sign in to comment.