Skip to content

Commit

Permalink
draft: Organize ros params as dataclass
Browse files Browse the repository at this point in the history
  • Loading branch information
elvout committed Feb 19, 2024
1 parent cdf58f3 commit 1463098
Showing 1 changed file with 44 additions and 0 deletions.
44 changes: 44 additions & 0 deletions yolov8_ros/parameters.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
from dataclasses import dataclass, field

from rclpy.node import Node


@dataclass
class YoloSkeletonRightWristNodeParams:
rgb_sub_topic: str = field(default="/camera/color/image_raw/compressed")
"""sensor_msgs/CompressedImage RGB topic to subscribe to."""

depth_sub_topic: str = field(default="/camera/aligned/depth_to_color/image_raw")
"""
sensor_msgs/Image aligned depth topic to subscribe to.
Images published to this topic must share the same intrinsic matrix as the
RGB image topic.
The uncompressed topic is used as there seems to be some difficulty
subscribing or decoding the compressed depth topic.
"""

camera_info_sub_topic: str = field(default="/camera/color/camera_info")
"""sensor_msgs/CameraInfo topic to subscribe to."""

stretch_robot_rotate_image_90deg: bool = field(default=True)
"""Whether to rotate the input images 90 degrees clockwise before inference.
This parameter exists because the Stretch robot's camera is mounted
sideways, and YOLOv8 does not appear to perform well on rotated images.
TODO: This could be implemented better, but it works for our use case at the
time of writing.
"""

@staticmethod
def read_from_ros(node: Node) -> "YoloSkeletonRightWristNodeParams":
params = YoloSkeletonRightWristNodeParams()

for param_name, default_value in vars(params).items():
ros_value = node.declare_parameter(param_name, default_value).value
assert type(ros_value) == type(default_value)
setattr(params, param_name, ros_value)

return params

0 comments on commit 1463098

Please sign in to comment.