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

QoS mismatch between gazebo_ros_camera and gazebo_ros_video #1218

Closed
BrettRD opened this issue Feb 1, 2021 · 6 comments
Closed

QoS mismatch between gazebo_ros_camera and gazebo_ros_video #1218

BrettRD opened this issue Feb 1, 2021 · 6 comments

Comments

@BrettRD
Copy link

BrettRD commented Feb 1, 2021

A QoS mismatch between camera and video plugins prevents an image topic from the camera being projected onto a surface.
The choice of QoS by the camera plugin also causes issues with rviz, rqt, and just about every other subscriber I've tried.

Pull request #926 would lead me to believe the camera plugin is the only topic in ROS that is using the correct QoS for its type, so I think this is a bug with gazebo_ros_video

Description
When using gazebo_ros_camera and after #1052, the camera plugin produces a message with QoS RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT which is expected,
but the video pluigin subscribes with QoS RMW_QOS_POLICY_RELIABILITY_RELIABLE
As a result, the subscription cannot receive any messages because of the QoS incompatibility.

To Reproduce
Create a SDF with camera and video plugins, remap them to the same topic

... one link
<plugin name="plugin_name" filename="libgazebo_ros_camera.so">
  <ros>
    <remapping>camera/image_raw:=cam_raw</remapping>
    <!-- the default topic name defies ~/ remapping but that's a different issue -->
  </ros>
... defaults
</plugin>

... another link
<plugin name="display" filename="libgazebo_ros_video.so">
  <ros>
    <remapping>~/image_raw:=cam_raw</remapping>
  </ros>
</plugin>

launch the world with

        launch.actions.ExecuteProcess(
            cmd=['gazebo', '--verbose', world]
        ),

inspect the topic with verbose output

$ ros2 topic info -v /cam_raw
Publisher count: 1
...
  Reliability: RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT
...
Subscription count: 2
...
  Reliability: RMW_QOS_POLICY_RELIABILITY_RELIABLE
...
  Reliability: RMW_QOS_POLICY_RELIABILITY_RELIABLE

The camera output is visible to ros2 topic echo, but it is not visible to rqt, and it is not displayed on the texture.

Expected behavior
The camera output should be visible in the texture rendered by gazebo_ros_video.

The subscriber in gazebo_ros_video should use a QoS of RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT either by convention, or by reading it from the image topic settings.

Screenshots
full topic info output

$ ros2 topic info -v /cam_raw 
Type: sensor_msgs/msg/Image

Publisher count: 1

Node name: _NODE_NAME_UNKNOWN_
Node namespace: _NODE_NAMESPACE_UNKNOWN_
Topic type: sensor_msgs/msg/Image
Endpoint type: PUBLISHER
GID: 01.0f.0c.eb.e5.60.02.00.01.00.00.00.00.00.31.03.00.00.00.00.00.00.00.00
QoS profile:
  Reliability: RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT
  Durability: RMW_QOS_POLICY_DURABILITY_VOLATILE
  Lifespan: 2147483651294967295 nanoseconds
  Deadline: 2147483651294967295 nanoseconds
  Liveliness: RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
  Liveliness lease duration: 2147483651294967295 nanoseconds

Subscription count: 2

Node name: _NODE_NAME_UNKNOWN_
Node namespace: _NODE_NAMESPACE_UNKNOWN_
Topic type: sensor_msgs/msg/Image
Endpoint type: SUBSCRIPTION
GID: 01.0f.0c.eb.e5.60.02.00.01.00.00.00.00.00.58.04.00.00.00.00.00.00.00.00
QoS profile:
  Reliability: RMW_QOS_POLICY_RELIABILITY_RELIABLE
  Durability: RMW_QOS_POLICY_DURABILITY_VOLATILE
  Lifespan: 2147483651294967295 nanoseconds
  Deadline: 2147483651294967295 nanoseconds
  Liveliness: RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
  Liveliness lease duration: 2147483651294967295 nanoseconds

Node name: _NODE_NAME_UNKNOWN_
Node namespace: _NODE_NAMESPACE_UNKNOWN_
Topic type: sensor_msgs/msg/Image
Endpoint type: SUBSCRIPTION
GID: 01.0f.0c.eb.e6.60.02.00.01.00.00.00.00.00.13.04.00.00.00.00.00.00.00.00
QoS profile:
  Reliability: RMW_QOS_POLICY_RELIABILITY_RELIABLE
  Durability: RMW_QOS_POLICY_DURABILITY_VOLATILE
  Lifespan: 2147483651294967295 nanoseconds
  Deadline: 2147483651294967295 nanoseconds
  Liveliness: RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
  Liveliness lease duration: 2147483651294967295 nanoseconds

Environment (please complete the following information):

  • OS: Ubuntu 20.04
  • Gazebo version: Gazebo 11 from apt
  • ROS version: Foxy
  • gazebo_ros_pkgs: compiled from source branch foxy at 7bf18c7ad727e0d5f3c80c4dee01fc1429c16093
  • glx server in use: server glx vendor string: NVIDIA Corporation

Additional context
https://index.ros.org/doc/ros2/Concepts/About-Quality-of-Service-Settings/
#1031
#926
ros-visualization/rqt_image_view#41
ros-visualization/rqt#187
http://docs.ros2.org/foxy/api/rclcpp/classrclcpp_1_1QoS.html
I'm interested in submitting a PR for this, and propagating QoS tolerance into rqt

@jacobperron
Copy link
Collaborator

In retrospect, I think all gazebo_ros pub/subs should use the default QoS profile (not the "sensor data" QoS profile). I.e. avoid best effort publishers, since most subscriptions (by default) will be expecting reliable transport.

@jacobperron
Copy link
Collaborator

@BrettRD Rather than updating the video plugin to use best effort, I think we should change all of the other plugins to publish reliable (use the default QoS settings). I believe that should fix the issue. Do you have time to make this change (I'm happy to review it)?

@BrettRD
Copy link
Author

BrettRD commented Feb 3, 2021

I have this patch on a local branch, I'll send a pull request shortly.

@jacobperron
Copy link
Collaborator

I believe this was resolved in ros2/geometry2#381 for Foxy and the forward port is pending review in #1235

@shonigmann
Copy link

just wanted to link to #1079, #1091, and #1092, in case others like me stumble across this issue when expecting a camera publisher to be Best Effort, and start wondering how to change the QoS for their simulated sensor so that it matches their hardware.

@nakai-omer
Copy link

nakai-omer commented Sep 28, 2023

@shonigmann Can you please add an explanation on how to change the QOS? I only see that it is possible, but finding it hard to find the way to change libgazebo_ros_camera for example to being best effort

UPDATE
Found a way to add it to the URDF:

<plugin name="${prefix}_controller" filename="libgazebo_ros_camera.so">
  <ros>
    <qos>
      <topic name="${prefix}/image_raw">
        <publisher>
          <reliability>best_effort</reliability>
        </publisher>
      </topic>
    </qos>
  </ros>
...

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants