diff --git a/app/imshow/imshow/imshow.py b/app/imshow/imshow/imshow.py index 76f968d..c31e775 100644 --- a/app/imshow/imshow/imshow.py +++ b/app/imshow/imshow/imshow.py @@ -3,17 +3,23 @@ import rclpy from cv_bridge import CvBridge from rclpy.node import Node +from rclpy.qos import HistoryPolicy, QoSProfile, ReliabilityPolicy from sensor_msgs.msg import CompressedImage class Imshow(Node): def __init__(self): super().__init__("imshow") + qos_profile = QoSProfile( + reliability=ReliabilityPolicy.BEST_EFFORT, + history=HistoryPolicy.KEEP_LAST, + depth=10, + ) self.subscription = self.create_subscription( CompressedImage, "camera_image", self.listener_callback, - 10, + qos_profile, ) self.bridge = CvBridge() diff --git a/device/camera_reader/camera_reader/camera.py b/device/camera_reader/camera_reader/camera.py index 4707acb..3371709 100644 --- a/device/camera_reader/camera_reader/camera.py +++ b/device/camera_reader/camera_reader/camera.py @@ -17,6 +17,11 @@ def __init__(self): ) assert isinstance(camera_id, int) self.cap = cv2.VideoCapture(camera_id) + # カメラ解像度の設定 + self.cap.set(cv2.CAP_PROP_FRAME_WIDTH, 640) + self.cap.set(cv2.CAP_PROP_FRAME_HEIGHT, 480) + # バッファサイズの設定 + self.cap.set(cv2.CAP_PROP_BUFFERSIZE, 1) self.bridge = CvBridge() if not self.cap.isOpened(): self.get_logger().error("Failed to open camera")