From 74268bc6da3f5688b8421022ad5b8d6c9465f695 Mon Sep 17 00:00:00 2001 From: Evan Flynn Date: Sun, 16 Jun 2024 11:53:53 -0700 Subject: [PATCH] Switch to use the recommended SensorDataQoS settings Signed-off-by: Evan Flynn --- src/ros2/usb_cam_node.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/ros2/usb_cam_node.cpp b/src/ros2/usb_cam_node.cpp index f8e8deda..7df52cff 100644 --- a/src/ros2/usb_cam_node.cpp +++ b/src/ros2/usb_cam_node.cpp @@ -46,7 +46,7 @@ UsbCamNode::UsbCamNode(const rclcpp::NodeOptions & node_options) m_compressed_img_msg(nullptr), m_image_publisher(std::make_shared( image_transport::create_camera_publisher(this, BASE_TOPIC_NAME, - rclcpp::QoS {100}.get_rmw_qos_profile()))), + rclcpp::SensorDataQoS().get_rmw_qos_profile()))), m_compressed_image_publisher(nullptr), m_compressed_cam_info_publisher(nullptr), m_parameters(), @@ -169,6 +169,9 @@ void UsbCamNode::init() return; } + // Note: these are only used to skip using the typical image_transport + // plugin and only publish the compressed image topic + // // if pixel format is equal to 'mjpeg', i.e. raw mjpeg stream, initialize compressed image message // and publisher if (m_parameters.pixel_format_name == "mjpeg") { @@ -176,10 +179,10 @@ void UsbCamNode::init() m_compressed_img_msg->header.frame_id = m_parameters.frame_id; m_compressed_image_publisher = this->create_publisher( - std::string(BASE_TOPIC_NAME) + "/compressed", rclcpp::QoS(100)); + std::string(BASE_TOPIC_NAME) + "/compressed", rclcpp::SensorDataQoS()); m_compressed_cam_info_publisher = this->create_publisher( - "camera_info", rclcpp::QoS(100)); + "camera_info", rclcpp::SensorDataQoS()); } m_image_msg->header.frame_id = m_parameters.frame_id;