ros2 / rmw_cyclonedds

ROS 2 RMW layer for Eclipse Cyclone DDS
Apache License 2.0
112 stars 91 forks source link

rmw cyclonedds implementation does not use asynchronous publishing #89

Open wjwwood opened 4 years ago

wjwwood commented 4 years ago

As discussed elsewhere (https://github.com/ros2/rmw_fastrtps/pull/343#pullrequestreview-346228522), the current best practice is to use the closest equivalent to the asynchronous publishing mode that some DDS implementations have for implementing rmw_publish(). Right now, this repository does not change the QoS for this when creating a publisher and therefore I assume it uses something like the synchronous publishing mode.

So a few questions:

If there is an equivalent mode then it would be best to switch to it by default, even if it has a negative performance impact for some cases.

We can/should separately decide if the best practice should be adjusted, but until that time we should try to keep our rmw implementations as consistent as possible.


And for some more background...

We prefer the asynchronous publishing mode (for now) because:

We're aware that there are performance (latency and throughput) considerations here, and we've already discussed having an option in the ROS API to allow this to be configurable, see: https://github.com/ros2/ros2/issues/255, or at least dynamic (smarter), see: https://github.com/ros2/rmw_connext/issues/190.

But until we decide to change something (and therefore change all the implementations together), I consider this a bug in the implementation of rmw_cyclonedds_cpp, i.e. that it does not implement publish with an "asynchronous publishing mode"-like mode (note this is not part of the DDS standard as far as I can see, but it is a common configuration).

wjwwood commented 4 years ago

Friendly ping, @eboasson you're likely the person who can most easily answer the questions for this issue, namely:

  • does cyclone have an "asynchronous publishing mode"-like setting?
  • if not, what is the blocking behavior of publishing in cyclone, or more generally what happens when you call publish?
dirk-thomas commented 4 years ago

@joespeed @eboasson Can you please provide us with a first response on these questions.

eboasson commented 4 years ago

@wjwwood, @dirk-thomas,

does cyclone have an "asynchronous publishing mode"-like setting?

Not currently — but it is something that it really should get, for more freedom in implementing various QoS settings and decoupling network flow control from application writes.

(For those who read this and have gone over the code with a fine comb, or do the latter having read this: it is not strictly true that it doesn't have such a mode, a little bit of code from a quick experiment I once did found its way into Cyclone and hasn't been removed yet. While I believe it works fine, I'd rather it doesn't get used as-is.)

if not, what is the blocking behavior of publishing in cyclone, or more generally what happens when you call publish?

I'm interpreting "blocking" here as waiting for some condition that depends on activity in an independent entity (e.g., the network or another process), and not on blocking on a mutex that by design must always become available shortly if the underlying platform behaves itself. (In this, listeners in Cyclone are a bit of a special case because they intentionally invoke application code on the middleware thread — else one might as well use a waitset — but the RMW layer doesn't use listeners and so this is a non-issue.)

Publishing is pretty straightforward, it involves:

  1. serialisation;
  2. waiting for the writer history cache to have room available and storing the new sample in it (for reliable writers), possibly pushing out data already present (for keep-last writers);
  3. adding the sample to the current packet-to-be-transmitted;
  4. transmitting that packet (once I get my asynchronous publishing support, the use of a latency budget change this and thereby allow packing multiple samples into larger datagrams, and that gives a huge improvement in efficiency for high sample rates);
  5. delivering it to all matching local readers and notifying waitsets.

Steps 2–4 are dependent on the existence of matching readers across the network — i.e., in other processes (or in the same if you use multiple domains that are masquerading as one). Absent the use of resource limits (which is the case here, as the ROS2 interface doesn't expose them), the two points where it can block are steps 2 and 4. A system consisting of a single process therefore never experiences blocking.

Re step 2, only reliable keep-all writers with matching reliable readers ever block, using a mechanism reminiscent of TCP: whenever writing an additional sample causes the number of unacknowledged bytes for that writer to cross a threshold (the "high water mark"), either of two things happens:

Once it starts transmitting a sample, it always gets transmitted in its entirety, even if the sample itself is far larger than the threshold. In such cases, you basically end up requiring an acknowledgement of each sample. In the absence of packet loss, the blocking times are roughly a round-trip time.

The "max blocking time" setting can cause it to abort waiting for the amount of unacknowledged data to drop below the low water mark and abandon transmitting the sample. ROS2 doesn't expose this setting (and the rmw_publish operation doesn't list a timeout as a possible error), and hence the RMW layer sets it to infinity. It will therefore block for however long it takes to receive the acknowledgements.

Re step 4, it uses a blocking socket for transmitting data to other processes/machines, and hence there will be some blocking if the network can't keep up with the application enqueuing it in the socket transmit buffer.

There is no fundamental reason for using a blocking socket, but if you'd change it to non-blocking mode you would get packet loss in the cases where it blocks today. For reliable subscriptions, that loss will generally be dealt with via retransmits but there will be a problem if the overruns occur very frequently: there is an "interesting" failure mode in the DDSI-RTPS protocol where a reader may fail to receive any data even though the writer is publishing continuously. It occurs when the reader never receives a sample as it is initially transmitted and moreover never manages to request a retransmit before the sample has been pushed out of the writer history cache by a subsequent write operation. Use of a non-blocking socket in combination with very large samples would make that a relatively likely failure mode.

And for best-effort mode and samples larger than the socket transmit buffer, one could probably reduce the overhead a little bit 😄 .

wjwwood commented 4 years ago

Thanks @eboasson for that in-depth answer.

These are the conclusions I draw from this (please check my math):


Since I still think it's a bug, I'll leave this open for now, until one of the resolutions can be done, but without selecting one of the approaches to resolve it, nor attaching a timeline.


I'll reiterate, though I think this is a bug, I don't want it to seem like I'm placing blame, I think it's totally reasonable to have overlooked this detail given the lack of documentation or tests checking this behavior.


Also, if we do add an option in the ROS API, then I think we still have an issue, which is what do we do for the default? If we default to async then cyclone will not work out of the box (until it has an async mode), but if we default to sync then Connext won't work out of the box with large data. We could have a "let the middleware decide" default option, which the user can pin one way or the other manually if they need to do so, but I really don't like the idea of that, just because it causes different behavior based on which implementation you select. Anyways, that's a discussion for that issue (https://github.com/ros2/ros2/issues/255).

ros-discourse commented 3 years ago

This issue has been mentioned on ROS Discourse. There might be relevant details there:

https://discourse.ros.org/t/rmw-fast-dds-publication-mode-sync-vs-async-and-how-to-change-it/17153/1