Skip to content

Commit

Permalink
Merge pull request #69 from rogy-AquaLab/speedup
Browse files Browse the repository at this point in the history
  • Loading branch information
H1rono authored Aug 17, 2024
2 parents f7bb884 + feb3cf3 commit fb19c0a
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 1 deletion.
8 changes: 7 additions & 1 deletion app/imshow/imshow/imshow.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()

Expand Down
5 changes: 5 additions & 0 deletions device/camera_reader/camera_reader/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand Down

0 comments on commit fb19c0a

Please sign in to comment.