Skip to content
This repository was archived by the owner on Jul 10, 2025. It is now read-only.
Merged
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
7 changes: 4 additions & 3 deletions gazebo_plugins/src/gazebo_ros_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _
image_transport::create_publisher(
impl_->ros_node_.get(),
camera_topic,
qos.get_publisher_qos(camera_topic).get_rmw_qos_profile()));
qos.get_publisher_qos(camera_topic, rclcpp::SensorDataQoS()).get_rmw_qos_profile()));

// TODO(louise) Uncomment this once image_transport::Publisher has a function to return the
// full topic.
Expand All @@ -208,7 +208,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _
impl_->image_pub_.push_back(
image_transport::create_publisher(
impl_->ros_node_.get(),
camera_topic, qos.get_publisher_qos(camera_topic).get_rmw_qos_profile()));
camera_topic,
qos.get_publisher_qos(camera_topic, rclcpp::SensorDataQoS()).get_rmw_qos_profile()));

// RCLCPP_INFO(
// impl_->ros_node_->get_logger(), "Publishing %s camera images to [%s]",
Expand All @@ -235,7 +236,7 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _
impl_->depth_image_pub_ = image_transport::create_publisher(
impl_->ros_node_.get(),
depth_topic,
qos.get_publisher_qos(depth_topic).get_rmw_qos_profile());
qos.get_publisher_qos(depth_topic, rclcpp::SensorDataQoS()).get_rmw_qos_profile());

// RCLCPP_INFO(impl_->ros_node_->get_logger(), "Publishing depth images to [%s]",
// impl_->depth_image_pub_.getTopic().c_str());
Expand Down