rosbridge_suite
rosbridge_suite copied to clipboard
Incompatible subscriber QoS when creating a subscription after a publisher
Description
In our setup multiple nodes publish ti a topic events
of type std_msgs/String
, all of them with durability VOLATILE
.
Using roslibjs we create a topic object:
var topicEvents = new ROSLIB.Topic({
ros: ros,
name: '/events',
messageType: 'std_msgs/String'
})
When calling
topicEvents.publish(mymsg);
The following warning is printed:
[rosbridge_websocket-1] [WARN] [1707742684.795099630] [rosbridge_websocket]: New publisher discovered on topic '/fsm/events', offering incompatible QoS. No messages will be received from it. Last incompatible policy: DURABILITY
This appears to be caused when creating a publisher first and then a subscription, the publisher is always created as transient local and the subscription inherits that property.
https://github.com/RobotWebTools/rosbridge_suite/blob/77d48c0876dd22d65bd1fab2b440d9d28350d5cc/rosbridge_library/src/rosbridge_library/internal/publishers.py#L105-L109
https://github.com/RobotWebTools/rosbridge_suite/blob/77d48c0876dd22d65bd1fab2b440d9d28350d5cc/rosbridge_library/src/rosbridge_library/internal/subscribers.py#L118-L122
- Library Version: 1.3.2
- ROS Version: humble
- Platform / OS: Ubuntu 22.04
Steps To Reproduce
volatile pub sub
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
class VolatilePubSub(Node):
def __init__(self):
super().__init__('volatile_pub_sub')
self.publisher_ = self.create_publisher(String, 'events', 10)
self.create_subscription = self.create_subscription(
String,
'events',
self.events_callback,
10
)
timer_period = 2 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0
def timer_callback(self):
msg = String()
msg.data = 'event-rclpy'
self.publisher_.publish(msg)
self.get_logger().info(f'Publishing: "{msg.data}"')
self.i += 1
def events_callback(self, msg: String):
self.get_logger().info(f"I Heard {msg.data}")
def main(args=None):
rclpy.init(args=args)
minimal_publisher = VolatilePubSub()
rclpy.spin(minimal_publisher)
# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
minimal_publisher.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
default roslibjs
#!/usr/bin/env node
// Connecting to ROS
var ROSLIB = require('roslib');
var ros = new ROSLIB.Ros({
url : 'ws://localhost:9090'
});
ros.on('connection', function() {
console.log('Connected to websocket server.');
});
ros.on('error', function(error) {
console.log('Error connecting to websocket server: ', error);
});
ros.on('close', function() {
console.log('Connection to websocket server closed.');
});
// Create topic object
var topicEvents = new ROSLIB.Topic({
ros: ros,
name: '/events',
messageType: 'std_msgs/String'
})
const mymsg = new ROSLIB.Message({ data: 'event-roslibjs' });
// Publish an event
topicEvents.publish(mymsg);
// Subscribe to it
topicEvents.subscribe(function (message) {
console.log('Received message ' + message.data);
});
console.log("Publishing event-roslibjs");
topicEvents.publish(mymsg);
Then create three terminals and run in the following order:
ros2 launch rosbridge_server rosbridge_websocket_launch.xml
python3 volatile_pub_sub.py
node default_js_pub.js
Expected Behavior
The publisher QoS
should match the ones of the already existing QoS
for a topic or should be able to be changed via the client. In addition subscription QoS
should also be able to be specified
Actual Behavior
A subscriber with incompatible QoS
is created
We are having issues with this as well. In our particular case we are making subscriptions from roslibjs. When the subscription is made from roslibjs before the rosbridge_server process sees the associated publisher, we end up with this QoS mismatch compatibility issue.
I haven't begun looking into the technical side at all yet, but conceptually I was thinking along the lines of 2 possible solutions:
- Add some sort of flag or paramter on the rosbridge_server to tell it to only create subscriptions/publishers lazily once it has seen another participant from which it can gleam the QoS (to keep this simple it would only do this the first time, and would not destroy or recreate those objects if the other side goes away and comes back, although it could be extended to do that in the future).
- Add explicit QoS settings to roslibjs as well as rosbridge_server. This one seems seems more complicated being as it would probably impact multiple projects... i haven't looked into the technical feasibility of this at all. (seems related: https://github.com/RobotWebTools/rosbridge_suite/issues/887)
Are there any other options that I may be overlooking? I would appreciate any leading guidance that anyone has to offer before we jump right into this.
Seems there has been a lot of talk about this subject over the past few years, as well as some attempts to fix it.
This seems to be a duplicate: https://github.com/RobotWebTools/rosbridge_suite/issues/769
@JayHerpin I agree with the solutions you have outlined
To me, the ideal solution seems like 2, but this comes with significant code changes...