From 39402198062f1abe8a146c70b04aec7c0015742b Mon Sep 17 00:00:00 2001 From: Mehmet Killioglu Date: Fri, 13 Oct 2023 16:04:17 +0300 Subject: [PATCH] Revert "Leave only ROS video feed topic" This reverts commit 2828b29d2eadb30b9e59b2c18dd06b9b7520b071. --- src/depthai_camera.cpp | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/src/depthai_camera.cpp b/src/depthai_camera.cpp index 72ff516..9ba4d8e 100644 --- a/src/depthai_camera.cpp +++ b/src/depthai_camera.cpp @@ -53,22 +53,22 @@ void DepthAICamera::Initialize() const std::string stream_control_topic = get_parameter("stream_control_topic").as_string();*/ _nn_directory = get_parameter("nn_directory").as_string(); -// _left_publisher = create_publisher("camera/left/image_raw", 10); -// _right_publisher = create_publisher("camera/right/image_raw", 10); -// _color_publisher = create_publisher("camera/color/image_raw", 10); -// _camera_info_publisher = create_publisher("camera/color/camera_info", 10); -// _depth_publisher = create_publisher("camera/depth/image_raw", 10); -// _passthrough_publisher = create_publisher("camera/color/image_passthrough", 10); + _left_publisher = create_publisher("camera/left/image_raw", 10); + _right_publisher = create_publisher("camera/right/image_raw", 10); + _color_publisher = create_publisher("camera/color/image_raw", 10); + _camera_info_publisher = create_publisher("camera/color/camera_info", 10); + _depth_publisher = create_publisher("camera/depth/image_raw", 10); + _passthrough_publisher = create_publisher("camera/color/image_passthrough", 10); -// _detection_roi_publisher = create_publisher( -// "camera/detections", 10); + _detection_roi_publisher = create_publisher( + "camera/detections", 10); _video_publisher = create_publisher( "camera/color/video", 10); -// _stream_command_subscriber = create_subscription( -// "camera/videostreamcmd", rclcpp::QoS(10).reliable(), -// std::bind(&DepthAICamera::VideoStreamCommand, this, _1)); + _stream_command_subscriber = create_subscription( + "camera/videostreamcmd", rclcpp::QoS(10).reliable(), + std::bind(&DepthAICamera::VideoStreamCommand, this, _1)); _auto_focus_timer = this->create_wall_timer(