[ros-users] [Discourse.ros.org] [Next Generation ROS] What should be the correct behavier of a "reliable" transmission? (throughput problem)

William Woodall ros.discourse at gmail.com
Tue Nov 13 18:36:07 UTC 2018



Setting the `RELIABILITY` QoS to `Reliable` only means that data is resent when the receiver fails to receive it. The behavior for how to do queueing when the receiver is slower than the sender is all in the history settings, as you've pointed out.

In ROS 1 the behavior is always like `KEEP_LAST` with a `depth` (in ROS 1 it's called `queue_size` which is a required argument when creating subscribers and publishers), for example see what happens in ROS 1 when the out going buffer is full:

https://github.com/ros/ros_comm/blob/eb7e686a9a58109087c956eed3cfa6f2ed3eec3d/clients/roscpp/src/libros/transport_subscriber_link.cpp#L198-L206

Most people just make larger queues when this is an issue.

I think it's for this reason we decided to use `KEEP_LAST` and a `depth` (believe the default is 10 or 100), as our default, in order to emulate the ROS 1 default behavior as closely as possible.

`KEEP_ALL` also has limits, but unlike `KEEP_LAST`'s `depth`, which always applies to each "instance" of samples, `KEEP_ALL` has two resource limits which always apply, `max_samples` and `max_samples_per_instance`. You could just set `max_samples_per_instance` to the same value as `depth` and then ideally `KEEP_ALL` and `KEEP_LAST` would only affect the strategy used when the queue is full, but you also need to set the `max_samples` to a reasonable value as well. When using `KEEP_ALL` you probably also want to set `max_instances` to a reasonable value, and so using `KEEP_ALL` is just more complicated.

I think ultimately the user needs to understand the difference in `KEEP_LAST` and `KEEP_ALL`, and I think that departing from the terminology used by DDS (to your suggestion "Should we somehow change the ROS2 definition and behavior?") is probably just going to be confusing. I also think that the default of `KEEP_LAST` is what ROS 1 users will be expecting by default, and I think that it's "safer" in the sense that the publisher is less likely to be negatively impacted by a misbehaving subscriber (e.g. a visualization tool over a lossy link) and therefore `KEEP_ALL` is more situational (like for use in services). For those reasons I think `KEEP_LAST` makes sense as the default, but it's definitely a subjective and opinionated position for the ROS 2 API to take.





---
[Visit Topic](https://discourse.ros.org/t/what-should-be-the-correct-behavier-of-a-reliable-transmission-throughput-problem/6826/2) or reply to this email to respond.




More information about the ros-users mailing list