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

publish with QoS reliable as default #1224

Merged
merged 2 commits into from
Feb 18, 2021
Merged
Show file tree
Hide file tree
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
2 changes: 1 addition & 1 deletion gazebo_plugins/src/gazebo_ros_bumper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ void GazeboRosBumper::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _

// Contact state publisher
impl_->pub_ = impl_->ros_node_->create_publisher<gazebo_msgs::msg::ContactsState>(
"bumper_states", qos.get_publisher_qos("bumper_states", rclcpp::SensorDataQoS()));
"bumper_states", qos.get_publisher_qos("bumper_states", rclcpp::SensorDataQoS().reliable()));

RCLCPP_INFO(
impl_->ros_node_->get_logger(), "Publishing contact states to [%s]",
Expand Down
21 changes: 10 additions & 11 deletions gazebo_plugins/src/gazebo_ros_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,9 +187,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _
const std::string camera_topic = impl_->camera_name_ + "/image_raw";
impl_->image_pub_.push_back(
image_transport::create_publisher(
impl_->ros_node_.get(),
camera_topic,
qos.get_publisher_qos(camera_topic, rclcpp::SensorDataQoS()).get_rmw_qos_profile()));
impl_->ros_node_.get(), camera_topic, qos.get_publisher_qos(
camera_topic, rclcpp::SensorDataQoS().reliable()).get_rmw_qos_profile()));

// TODO(louise) Uncomment this once image_transport::Publisher has a function to return the
// full topic.
Expand All @@ -201,7 +200,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _
const std::string camera_info_topic = impl_->camera_name_ + "/camera_info";
impl_->camera_info_pub_.push_back(
impl_->ros_node_->create_publisher<sensor_msgs::msg::CameraInfo>(
camera_info_topic, qos.get_publisher_qos(camera_info_topic, rclcpp::SensorDataQoS())));
camera_info_topic, qos.get_publisher_qos(
camera_info_topic, rclcpp::SensorDataQoS().reliable())));

RCLCPP_INFO(
impl_->ros_node_->get_logger(), "Publishing camera info to [%s]",
Expand All @@ -214,9 +214,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _
// Image publisher
impl_->image_pub_.push_back(
image_transport::create_publisher(
impl_->ros_node_.get(),
camera_topic,
qos.get_publisher_qos(camera_topic, rclcpp::SensorDataQoS()).get_rmw_qos_profile()));
impl_->ros_node_.get(), camera_topic, qos.get_publisher_qos(
camera_topic, rclcpp::SensorDataQoS().reliable()).get_rmw_qos_profile()));

// RCLCPP_INFO(
// impl_->ros_node_->get_logger(), "Publishing %s camera images to [%s]",
Expand All @@ -228,7 +227,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _
// Camera info publisher
impl_->camera_info_pub_.push_back(
impl_->ros_node_->create_publisher<sensor_msgs::msg::CameraInfo>(
camera_info_topic, qos.get_publisher_qos(camera_info_topic, rclcpp::SensorDataQoS())));
camera_info_topic, qos.get_publisher_qos(
camera_info_topic, rclcpp::SensorDataQoS().reliable())));

RCLCPP_INFO(
impl_->ros_node_->get_logger(), "Publishing %s camera info to [%s]",
Expand All @@ -241,9 +241,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _
const std::string depth_topic = impl_->camera_name_ + "/depth/image_raw";
// Depth image publisher
impl_->depth_image_pub_ = image_transport::create_publisher(
impl_->ros_node_.get(),
depth_topic,
qos.get_publisher_qos(depth_topic, rclcpp::SensorDataQoS()).get_rmw_qos_profile());
impl_->ros_node_.get(), depth_topic, qos.get_publisher_qos(
depth_topic, rclcpp::SensorDataQoS().reliable()).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
2 changes: 1 addition & 1 deletion gazebo_plugins/src/gazebo_ros_gps_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ void GazeboRosGpsSensor::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPt
}

impl_->pub_ = impl_->ros_node_->create_publisher<sensor_msgs::msg::NavSatFix>(
"~/out", qos.get_publisher_qos("~/out", rclcpp::SensorDataQoS()));
"~/out", qos.get_publisher_qos("~/out", rclcpp::SensorDataQoS().reliable()));

// Create message to be reused
auto msg = std::make_shared<sensor_msgs::msg::NavSatFix>();
Expand Down
2 changes: 1 addition & 1 deletion gazebo_plugins/src/gazebo_ros_imu_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ void GazeboRosImuSensor::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPt
}

impl_->pub_ = impl_->ros_node_->create_publisher<sensor_msgs::msg::Imu>(
"~/out", qos.get_publisher_qos("~/out", rclcpp::SensorDataQoS()));
"~/out", qos.get_publisher_qos("~/out", rclcpp::SensorDataQoS().reliable()));

// Create message to be reused
auto msg = std::make_shared<sensor_msgs::msg::Imu>();
Expand Down
3 changes: 2 additions & 1 deletion gazebo_plugins/src/gazebo_ros_p3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,8 @@ void GazeboRosP3D::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf)
}

impl_->pub_ = impl_->ros_node_->create_publisher<nav_msgs::msg::Odometry>(
impl_->topic_name_, qos.get_publisher_qos(impl_->topic_name_, rclcpp::SensorDataQoS()));
impl_->topic_name_, qos.get_publisher_qos(
impl_->topic_name_, rclcpp::SensorDataQoS().reliable()));
impl_->topic_name_ = impl_->pub_->get_topic_name();
RCLCPP_DEBUG(
impl_->ros_node_->get_logger(), "Publishing on topic [%s]", impl_->topic_name_.c_str());
Expand Down
2 changes: 1 addition & 1 deletion gazebo_plugins/src/gazebo_ros_ray_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ void GazeboRosRaySensor::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPt
const gazebo_ros::QoS & qos = impl_->ros_node_->get_qos();

// Get QoS profile for the publisher
rclcpp::QoS pub_qos = qos.get_publisher_qos("~/out", rclcpp::SensorDataQoS());
rclcpp::QoS pub_qos = qos.get_publisher_qos("~/out", rclcpp::SensorDataQoS().reliable());

// Get tf frame for output
impl_->frame_name_ = gazebo_ros::SensorFrameID(*_sensor, *_sdf);
Expand Down