diff --git a/image_transport/src/camera_subscriber.cpp b/image_transport/src/camera_subscriber.cpp index 3075564a..b90a6b4e 100644 --- a/image_transport/src/camera_subscriber.cpp +++ b/image_transport/src/camera_subscriber.cpp @@ -122,7 +122,8 @@ CameraSubscriber::CameraSubscriber( std::string info_topic = getCameraInfoTopic(image_topic); impl_->image_sub_.subscribe(node, image_topic, transport, custom_qos); - impl_->info_sub_.subscribe(node, info_topic, custom_qos); + impl_->info_sub_.subscribe(node, info_topic, + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos))); impl_->sync_.connectInput(impl_->image_sub_, impl_->info_sub_); impl_->sync_.registerCallback(std::bind(callback, std::placeholders::_1, std::placeholders::_2));