Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Switch to use the recommended SensorDataQoS settings #339

Open
wants to merge 1 commit into
base: ros2
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 6 additions & 3 deletions src/ros2/usb_cam_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ UsbCamNode::UsbCamNode(const rclcpp::NodeOptions & node_options)
m_compressed_img_msg(nullptr),
m_image_publisher(std::make_shared<image_transport::CameraPublisher>(
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(),
Expand Down Expand Up @@ -169,17 +169,20 @@ 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") {
m_compressed_img_msg.reset(new sensor_msgs::msg::CompressedImage());
m_compressed_img_msg->header.frame_id = m_parameters.frame_id;
m_compressed_image_publisher =
this->create_publisher<sensor_msgs::msg::CompressedImage>(
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<sensor_msgs::msg::CameraInfo>(
"camera_info", rclcpp::QoS(100));
"camera_info", rclcpp::SensorDataQoS());
}

m_image_msg->header.frame_id = m_parameters.frame_id;
Expand Down
Loading